From 5d5b5ff3ec7bb571bdb364b3253a578154b6f5e0 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 28 Feb 2025 17:57:37 +0900 Subject: [PATCH 01/17] feat(autoware_lanelet2_utility): add kind Signed-off-by: Mamoru Sobue --- .../autoware_lanelet2_utility/CMakeLists.txt | 33 + common/autoware_lanelet2_utility/README.md | 36 + .../autoware_lanelet2_utility/kind.hpp | 67 + .../media/nomenclature/adjacent.drawio.svg | 208 ++ .../boundary_entry_exit.drawio.svg | 76 + .../media/nomenclature/bundle.drawio.svg | 506 +++++ .../media/nomenclature/connected.drawio.svg | 70 + .../media/nomenclature/driving.drawio.svg | 424 ++++ .../media/nomenclature/following.drawio.svg | 604 ++++++ .../media/nomenclature/merging.drawio.svg | 289 +++ .../nomenclature/nomenclature.drawio.svg | 693 +++++++ .../media/nomenclature/opposite.drawio.svg | 411 ++++ .../opposite_direction.drawio.svg | 616 ++++++ .../media/nomenclature/previous.drawio.svg | 481 +++++ .../nomenclature/same_direction.drawio.svg | 209 ++ .../media/nomenclature/sequence.drawio.svg | 562 ++++++ .../media/nomenclature/sibling.drawio.svg | 603 ++++++ common/autoware_lanelet2_utility/package.xml | 25 + .../sample_map/road_shoulder/highway.osm | 346 ++++ .../sample_map/road_shoulder/pudo.osm | 1753 +++++++++++++++++ .../scripts/lanelet_anonymization_local.py | 76 + common/autoware_lanelet2_utility/src/kind.cpp | 42 + .../autoware_lanelet2_utility/test/kind.cpp | 80 + .../test/local_projector.hpp | 54 + 24 files changed, 8264 insertions(+) create mode 100644 common/autoware_lanelet2_utility/CMakeLists.txt create mode 100644 common/autoware_lanelet2_utility/README.md create mode 100644 common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/kind.hpp create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/adjacent.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/boundary_entry_exit.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/bundle.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/connected.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/driving.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/following.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/merging.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/nomenclature.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/opposite.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/opposite_direction.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/previous.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/same_direction.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/sequence.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/nomenclature/sibling.drawio.svg create mode 100644 common/autoware_lanelet2_utility/package.xml create mode 100644 common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm create mode 100644 common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm create mode 100755 common/autoware_lanelet2_utility/scripts/lanelet_anonymization_local.py create mode 100644 common/autoware_lanelet2_utility/src/kind.cpp create mode 100644 common/autoware_lanelet2_utility/test/kind.cpp create mode 100644 common/autoware_lanelet2_utility/test/local_projector.hpp diff --git a/common/autoware_lanelet2_utility/CMakeLists.txt b/common/autoware_lanelet2_utility/CMakeLists.txt new file mode 100644 index 000000000..da576dc0b --- /dev/null +++ b/common/autoware_lanelet2_utility/CMakeLists.txt @@ -0,0 +1,33 @@ +cmake_minimum_required(VERSION 3.8) +project(autoware_lanelet2_utility) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/kind.cpp +) + +if(BUILD_TESTING) + find_package(ament_cmake_ros REQUIRED) + ament_auto_find_test_dependencies() + + file(GLOB_RECURSE test_files test/*.cpp) + + foreach (test_file IN LISTS test_files) + get_filename_component(test_file_name ${test_file} NAME) + ament_auto_add_gtest(${test_file_name}_${PROJECT_NAME} ${test_file}) + target_link_libraries(${test_file_name}_${PROJECT_NAME} + ${PROJECT_NAME} + ) + endforeach() +endif() + +ament_auto_package(INSTALL_TO_SHARE + sample_map +) + +install(PROGRAMS + scripts/lanelet_anonymization_local.py + DESTINATION lib/${PROJECT_NAME} +) diff --git a/common/autoware_lanelet2_utility/README.md b/common/autoware_lanelet2_utility/README.md new file mode 100644 index 000000000..89de145ba --- /dev/null +++ b/common/autoware_lanelet2_utility/README.md @@ -0,0 +1,36 @@ +# autoware_lanelet2_utility + +## Nomenclature + +This package aims to strictly define the meaning of several words To disambiguate the documentation and API's scope. In the table below, `codespace` words are given specific meanings when used in API and API description. _italic_ words are emphasized to indicate that it refers to social common sense which often comes with ambiguity. To help clarify the meaning, illustration is provided. "Lanelet" refers to the entity of a`lanelet::Lanelet` object in order to distinguish with the word "lane" used in social customs. `A` and `B` stands for Lanelets objects. + +| Word | Meaning | Illustration | +| --------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `driving` | The vehicle position belongs to the designated Lanelet. | In each map, green Lanelet are the `driving` lanes of the vehicle.
![driving](./media/nomenclature/driving.drawio.svg) | +| `boundary`,
`entry`,
`exit` | The `boundary` of a Lanelet refers to the left or right Linestring. | ![boundary_entry_exit](./media/nomenclature/boundary_entry_exit.drawio.svg) | +| `adjacent` | If A is `adjacent` to B, A and B share a common `boundary` with same direction either on the left or right side. | In each map, orange Lanelet is `adjacent` to green Lanelet.
![adjacent](./media/nomenclature/adjacent.drawio.svg) | +| `same_direction` | Lanelet A and Lanelet B are `same_direction` if A and B are directly or indirectly `adjacent` to each other. | In each map, orange Lanelets are `same_dirction` as green Lanelet.
![same_direction](./media/nomenclature/same_direction.drawio.svg) | +| `bundle` | A `bundle` refers to a transitive closure set of Lanelets which are `same_direction` to each other. | The enclosed sets of Lanelets are `bundle`s.
![bundle](./media/nomenclature/bundle.drawio.svg) | +| `opposite` | If A is `opposite` to B, A and B share a common `boundary` with opposite direction. | In the first map, green Lanelet and orange Lanelet are `opposite` to each other.
In the second map, two red Lanelets are not `opposite` relation because they do not share a common LineString.
![opposite](./media/nomenclature/opposite.drawio.svg) | +| `opposite_direction` | If A and B are `opposite_direction`, the bundle of A and B are directly `opposite` to each other. | In the each map, green Lanelet and orange Lanelet are `opposite_direction` becauase their `bundle`s(enclosed in dotted line) are `opposite` relation.
![opposite_direction](./media/nomenclature/opposite_direction.drawio.svg) | +| `connected` | A is `connected` to(from) B if and only if the `exit`(`entry`) of A is identical to the `entry`(`exit`) of B. | A is connected to B, and B is connected from A.
![connected](./media/nomenclature/connected.drawio.svg) | +| `following` | The `following` Lanelets of A is the list of Lanelets to which A is `connected`. | In each map, orange Lanelets are the `following` of green Lanelet.
![following](./media/nomenclature/following.drawio.svg) | +| `previous` | The `previous` Lanelets of A is the list of Lanelets from which A is `connected`. | In each map, orange Lanelets are the `previous` of green Lanelet.
![previous](./media/nomenclature/previous.drawio.svg) | +| `conflicting` | A is `conflicting` with B if A and B are geometrically intersecting. | | +| `merging` | A is said to be `merging` Lanelet of B if and only if A is `conflicting` with B and both A and B are connected to a common Lanelet. | In each map, one of the orange Lanelet is a `mergin` Lanelet of the other orange Lanelet.
![merging](./media/nomenclature/merging.drawio.svg) | +| `sibling` | The designated Lanelets are refered to as `sibling` if all of them are `connected` from a common Lanelet. | In each map, orange Lanelets are `sibling`s.
![sibling](./media/nomenclature/sibling.drawio.svg) | +| `oncoming` | TBD | TBD | +| `upcoming` | TBD | TBD | +| `sequence` | `sequence` is a list of Lanelets whose each element is `connected from` or `adjacent to` the previous element. | ![sequence](./media/nomenclature/sequence.drawio.svg) | + +## API description + +## How to craft test map + +On the VMB, create the map in local projector(or convert it to local projector from MGRS projector) and save the file as ``. Next, select the point to use as (0.0, 0.0) and pass its `` and run + +```bash +ros2 run autoware_lanelet2_utility lanelet_anonymization_local.py +``` + +Then the coordinate of the specified point is (0, 0) on the loaded map diff --git a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/kind.hpp b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/kind.hpp new file mode 100644 index 000000000..1d5225ff4 --- /dev/null +++ b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/kind.hpp @@ -0,0 +1,67 @@ +// Copyright 2025 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_UTILITY__KIND_HPP_ +#define AUTOWARE_LANELET2_UTILITY__KIND_HPP_ + +#include + +namespace autoware::lanelet2_utility +{ + +inline namespace kind +{ +static constexpr const char * k_road_lane_type = "road"; +static constexpr const char * k_shoulder_lane_type = "road_shoulder"; +static constexpr const char * k_bicycle_lane_type = "bicycle_lane"; + +/* + * TODO(soblin): distinguish road lane type +class RoadLane : public lanelet::ConstLanelet +{ +}; + +class RoadShoulderLane : public lanelet::ConstLanelet +{ +}; + +class BicycleLane : public lanelet::ConstLanelet +{ +}; +*/ + +/** + * @brief check if the given lanelet type has "road" subtype + * @param [in] lanelet input lanelet + * @return if the lanelet is road or not + */ +bool is_road_lane(const lanelet::ConstLanelet & lanelet); + +/** + * @brief check if the given lanelet type has "road_shoulder" subtype + * @param [in] lanelet input lanelet + * @return if the lanelet is road_shoulder or not + */ +bool is_shoulder_lane(const lanelet::ConstLanelet & lanelet); + +/** + * @brief check if the given lanelet type has "bicycle_lane" subtype + * @param [in] lanelet input lanelet + * @return if the lanelet is bicicye_lane or not + */ +bool is_bicycle_lane(const lanelet::ConstLanelet & lanelet); +} // namespace kind + +} // namespace autoware::lanelet2_utility +#endif // AUTOWARE_LANELET2_UTILITY__KIND_HPP_ diff --git a/common/autoware_lanelet2_utility/media/nomenclature/adjacent.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/adjacent.drawio.svg new file mode 100644 index 000000000..82f2bd174 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/adjacent.drawio.svg @@ -0,0 +1,208 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/media/nomenclature/boundary_entry_exit.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/boundary_entry_exit.drawio.svg new file mode 100644 index 000000000..9ef3ceff7 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/boundary_entry_exit.drawio.svg @@ -0,0 +1,76 @@ + + + + + + + + + + + + + + + + + +
+
+
+ boundary +
+
+
+
+ boundary +
+
+ + + + + +
+
+
+ exit +
+
+
+
+ exit +
+
+ + + + + +
+
+
+ entry +
+
+
+
+ entry +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/common/autoware_lanelet2_utility/media/nomenclature/bundle.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/bundle.drawio.svg new file mode 100644 index 000000000..dfcb29f47 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/bundle.drawio.svg @@ -0,0 +1,506 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/media/nomenclature/connected.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/connected.drawio.svg new file mode 100644 index 000000000..8d6bfd6b1 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/connected.drawio.svg @@ -0,0 +1,70 @@ + + + + + + + + + + + + + + + + + + + + + +
+
+
+ B +
+
+
+
+ B +
+
+ + + + +
+
+
+ A +
+
+
+
+ A +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/common/autoware_lanelet2_utility/media/nomenclature/driving.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/driving.drawio.svg new file mode 100644 index 000000000..3bc1bbac7 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/driving.drawio.svg @@ -0,0 +1,424 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/media/nomenclature/following.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/following.drawio.svg new file mode 100644 index 000000000..603257410 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/following.drawio.svg @@ -0,0 +1,604 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/media/nomenclature/merging.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/merging.drawio.svg new file mode 100644 index 000000000..1dbee5f82 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/merging.drawio.svg @@ -0,0 +1,289 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/media/nomenclature/nomenclature.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/nomenclature.drawio.svg new file mode 100644 index 000000000..dca28ee2d --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/nomenclature.drawio.svg @@ -0,0 +1,693 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/media/nomenclature/opposite.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/opposite.drawio.svg new file mode 100644 index 000000000..d5fb01c5e --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/opposite.drawio.svg @@ -0,0 +1,411 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/media/nomenclature/opposite_direction.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/opposite_direction.drawio.svg new file mode 100644 index 000000000..b304541b5 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/opposite_direction.drawio.svg @@ -0,0 +1,616 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/media/nomenclature/previous.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/previous.drawio.svg new file mode 100644 index 000000000..555128ece --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/previous.drawio.svg @@ -0,0 +1,481 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/media/nomenclature/same_direction.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/same_direction.drawio.svg new file mode 100644 index 000000000..552358977 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/same_direction.drawio.svg @@ -0,0 +1,209 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/media/nomenclature/sequence.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/sequence.drawio.svg new file mode 100644 index 000000000..dfca466e7 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/sequence.drawio.svg @@ -0,0 +1,562 @@ + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 2 +
+
+
+
+ 2 +
+
+ + + + + +
+
+
+ 1 +
+
+
+
+ 1 +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 6 +
+
+
+
+ 6 +
+
+ + + + + + + + + + + + +
+
+
+ 1 +
+
+
+
+ 1 +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 4 +
+
+
+
+ 4 +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 2 +
+
+
+
+ 2 +
+
+ + + + +
+
+
+ 4 +
+
+
+
+ 4 +
+
+ + + + +
+
+
+ 3 +
+
+
+
+ 3 +
+
+ + + + +
+
+
+ 5 +
+
+
+
+ 5 +
+
+ + + + +
+
+
+ 3 +
+
+
+
+ 3 +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/common/autoware_lanelet2_utility/media/nomenclature/sibling.drawio.svg b/common/autoware_lanelet2_utility/media/nomenclature/sibling.drawio.svg new file mode 100644 index 000000000..88794ff6a --- /dev/null +++ b/common/autoware_lanelet2_utility/media/nomenclature/sibling.drawio.svg @@ -0,0 +1,603 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/package.xml b/common/autoware_lanelet2_utility/package.xml new file mode 100644 index 000000000..a7009db32 --- /dev/null +++ b/common/autoware_lanelet2_utility/package.xml @@ -0,0 +1,25 @@ + + + + autoware_lanelet2_utility + 0.0.0 + The autoware_lanelet2_utility package + Mamoru Sobue + Apache License 2.0 + + Mamoru Sobue + + ament_cmake_auto + autoware_cmake + + autoware_lanelet2_extension + visualization_msgs + + ament_cmake_ros + ament_index_cpp + autoware_pyplot + + + ament_cmake + + diff --git a/common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm b/common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm new file mode 100644 index 000000000..f28997118 --- /dev/null +++ b/common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm @@ -0,0 +1,346 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm b/common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm new file mode 100644 index 000000000..669f1c0f8 --- /dev/null +++ b/common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm @@ -0,0 +1,1753 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/scripts/lanelet_anonymization_local.py b/common/autoware_lanelet2_utility/scripts/lanelet_anonymization_local.py new file mode 100755 index 000000000..3b77b9533 --- /dev/null +++ b/common/autoware_lanelet2_utility/scripts/lanelet_anonymization_local.py @@ -0,0 +1,76 @@ +#!/usr/bin/env python3 + +# 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. + +import argparse +import xml.etree.ElementTree as ET + +origin_offset_x = 0.0 +origin_offset_y = 0.0 + + +def update_osm_latlon(osm_file, output_file, origin_id): + tree = ET.parse(osm_file) + root = tree.getroot() + + old_origin_local_xy = None + + for node in root.findall("node"): + local_x_tag = node.find(".//tag[@k='local_x']") + local_y_tag = node.find(".//tag[@k='local_y']") + + if node.attrib["id"] == str(origin_id): + old_origin_local_xy = (float(local_x_tag.attrib["v"]), float(local_y_tag.attrib["v"])) + local_x_tag.set("v", str(0.0 - origin_offset_x)) + local_y_tag.set("v", str(0.0 - origin_offset_y)) + break + + if old_origin_local_xy is None: + print(f"could not find point of id {origin_id}") + return + + (old_origin_x, old_origin_y) = old_origin_local_xy + for node in root.findall("node"): + # make origin value exactly (0.0, 0.0) + if node.attrib["id"] == str(origin_id): + continue + + local_x_tag = node.find(".//tag[@k='local_x']") + local_y_tag = node.find(".//tag[@k='local_y']") + + local_x = float(local_x_tag.attrib["v"]) + local_y = float(local_y_tag.attrib["v"]) + adj_local_x = local_x - old_origin_x + adj_local_y = local_y - old_origin_y + + local_x_tag.set("v", str(adj_local_x - origin_offset_x)) + local_y_tag.set("v", str(adj_local_y - origin_offset_y)) + node.set("lat", str(0.0)) + node.set("lon", str(0.0)) + + tree.write(output_file, encoding="UTF-8", xml_declaration=True) + print(f"Updated OSM file created: {output_file}") + + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + description="Update OSM file with new origin and adjusted coordinates." + ) + parser.add_argument("input_osm", help="Path to the input OSM file") + parser.add_argument("output_osm", help="Path to the output OSM file") + parser.add_argument("origin_id", help="id of the point to reset as origin", type=int) + args = parser.parse_args() + + update_osm_latlon(args.input_osm, args.output_osm, args.origin_id) diff --git a/common/autoware_lanelet2_utility/src/kind.cpp b/common/autoware_lanelet2_utility/src/kind.cpp new file mode 100644 index 000000000..12a6e98e1 --- /dev/null +++ b/common/autoware_lanelet2_utility/src/kind.cpp @@ -0,0 +1,42 @@ +// Copyright 2025 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 + +#include + +namespace autoware::lanelet2_utility +{ + +inline namespace kind +{ +bool is_road_lane(const lanelet::ConstLanelet & lanelet) +{ + return strcmp(lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_road_lane_type) == + 0; +} + +bool is_shoulder_lane(const lanelet::ConstLanelet & lanelet) +{ + return strcmp( + lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_shoulder_lane_type) == 0; +} + +bool is_bicycle_lane(const lanelet::ConstLanelet & lanelet) +{ + return strcmp( + lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_bicycle_lane_type) == 0; +} +} // namespace kind +} // namespace autoware::lanelet2_utility diff --git a/common/autoware_lanelet2_utility/test/kind.cpp b/common/autoware_lanelet2_utility/test/kind.cpp new file mode 100644 index 000000000..d4787b8bd --- /dev/null +++ b/common/autoware_lanelet2_utility/test/kind.cpp @@ -0,0 +1,80 @@ +// Copyright 2025 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 "local_projector.hpp" + +#include +#include +#include + +#include +#include + +#include +#include + +namespace fs = std::filesystem; + +class TestWithRoadShoulderHighwayMap : public ::testing::Test +{ +protected: + lanelet::LaneletMapConstPtr lanelet_map_ptr_{nullptr}; + + void SetUp() override + { + const auto sample_map_dir = + fs::path(ament_index_cpp::get_package_share_directory("autoware_lanelet2_utility")) / + "sample_map"; + const auto road_shoulder_highway_map_path = sample_map_dir / "road_shoulder" / "highway.osm"; + + lanelet_map_ptr_ = load_local_coordinate_map(road_shoulder_highway_map_path.string()); + } +}; + +TEST_F(TestWithRoadShoulderHighwayMap, LoadCheck) +{ + const auto point8 = lanelet_map_ptr_->pointLayer.get(8); + EXPECT_EQ(point8.x(), 0.0); + EXPECT_EQ(point8.y(), 0.0); + const auto point10 = lanelet_map_ptr_->pointLayer.get(10); + EXPECT_EQ(point10.x(), 4.0); + EXPECT_EQ(point10.y(), 0.0); + const auto point15 = lanelet_map_ptr_->pointLayer.get(15); + EXPECT_EQ(point15.x(), 8.0); + EXPECT_EQ(point15.y(), 0.0); +} + +TEST_F(TestWithRoadShoulderHighwayMap, is_road_lane) +{ + const auto ll = lanelet_map_ptr_->laneletLayer.get(1275); + EXPECT_EQ(autoware::lanelet2_utility::is_road_lane(ll), true); + EXPECT_EQ(autoware::lanelet2_utility::is_shoulder_lane(ll), false); + EXPECT_EQ(autoware::lanelet2_utility::is_bicycle_lane(ll), false); +} + +TEST_F(TestWithRoadShoulderHighwayMap, is_shoulder_lane) +{ + const auto ll = lanelet_map_ptr_->laneletLayer.get(67); + EXPECT_EQ(autoware::lanelet2_utility::is_road_lane(ll), false); + EXPECT_EQ(autoware::lanelet2_utility::is_shoulder_lane(ll), true); + EXPECT_EQ(autoware::lanelet2_utility::is_bicycle_lane(ll), false); +} + +// TODO(soblin): add and use bicycle lane map + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/common/autoware_lanelet2_utility/test/local_projector.hpp b/common/autoware_lanelet2_utility/test/local_projector.hpp new file mode 100644 index 000000000..00e56e8cb --- /dev/null +++ b/common/autoware_lanelet2_utility/test/local_projector.hpp @@ -0,0 +1,54 @@ +// Copyright 2025 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 LOCAL_PROJECTOR_HPP_ +#define LOCAL_PROJECTOR_HPP_ + +#include +#include +#include + +#include +#include + +class LocalProjector : public lanelet::Projector +{ +public: + LocalProjector() : Projector(lanelet::Origin(lanelet::GPSPoint{})) {} + + lanelet::BasicPoint3d forward(const lanelet::GPSPoint & gps) const override // NOLINT + { + return lanelet::BasicPoint3d{0.0, 0.0, gps.ele}; + } + + [[nodiscard]] lanelet::GPSPoint reverse(const lanelet::BasicPoint3d & point) const override + { + return lanelet::GPSPoint{0.0, 0.0, point.z()}; + } +}; + +inline lanelet::LaneletMapConstPtr load_local_coordinate_map(const std::string & path) +{ + lanelet::ErrorMessages errors{}; + LocalProjector projector; + auto lanelet_map_ptr_mut = lanelet::load(path, projector, &errors); + for (auto point : lanelet_map_ptr_mut->pointLayer) { + point.x() = point.attribute("local_x").asDouble().value(); + point.y() = point.attribute("local_y").asDouble().value(); + } + + return lanelet::LaneletMapConstPtr{std::move(lanelet_map_ptr_mut)}; +} + +#endif // LOCAL_PROJECTOR_HPP_ From ae88cb101b2e8885dfcd7ea8d09b099104a8a61a Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 3 Mar 2025 04:45:28 +0900 Subject: [PATCH 02/17] adding topology, API description Signed-off-by: Mamoru Sobue --- common/autoware_lanelet2_utility/README.md | 164 ++++- .../autoware_lanelet2_utility/kind.hpp | 7 +- .../autoware_lanelet2_utility/topology.hpp | 149 ++++ .../media/api/left_lanelet.drawio.svg | 648 +++++++++++++++++ .../media/api/left_lanelets.drawio.svg | 672 ++++++++++++++++++ .../media/api/leftmost_lanelet.drawio.svg | 629 ++++++++++++++++ .../media/api/right_lanelets.drawio.svg | 470 ++++++++++++ .../api/right_opposite_lanelet.drawio.svg | 640 +++++++++++++++++ .../media/api/rightmost_lanelet.drawio.svg | 435 ++++++++++++ common/autoware_lanelet2_utility/src/kind.cpp | 4 - .../src/topology.cpp | 70 ++ 11 files changed, 3858 insertions(+), 30 deletions(-) create mode 100644 common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp create mode 100644 common/autoware_lanelet2_utility/media/api/left_lanelet.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/api/left_lanelets.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/api/leftmost_lanelet.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/api/right_lanelets.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/api/right_opposite_lanelet.drawio.svg create mode 100644 common/autoware_lanelet2_utility/media/api/rightmost_lanelet.drawio.svg create mode 100644 common/autoware_lanelet2_utility/src/topology.cpp diff --git a/common/autoware_lanelet2_utility/README.md b/common/autoware_lanelet2_utility/README.md index 89de145ba..2c2955a3f 100644 --- a/common/autoware_lanelet2_utility/README.md +++ b/common/autoware_lanelet2_utility/README.md @@ -2,29 +2,153 @@ ## Nomenclature -This package aims to strictly define the meaning of several words To disambiguate the documentation and API's scope. In the table below, `codespace` words are given specific meanings when used in API and API description. _italic_ words are emphasized to indicate that it refers to social common sense which often comes with ambiguity. To help clarify the meaning, illustration is provided. "Lanelet" refers to the entity of a`lanelet::Lanelet` object in order to distinguish with the word "lane" used in social customs. `A` and `B` stands for Lanelets objects. - -| Word | Meaning | Illustration | -| --------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `driving` | The vehicle position belongs to the designated Lanelet. | In each map, green Lanelet are the `driving` lanes of the vehicle.
![driving](./media/nomenclature/driving.drawio.svg) | -| `boundary`,
`entry`,
`exit` | The `boundary` of a Lanelet refers to the left or right Linestring. | ![boundary_entry_exit](./media/nomenclature/boundary_entry_exit.drawio.svg) | -| `adjacent` | If A is `adjacent` to B, A and B share a common `boundary` with same direction either on the left or right side. | In each map, orange Lanelet is `adjacent` to green Lanelet.
![adjacent](./media/nomenclature/adjacent.drawio.svg) | -| `same_direction` | Lanelet A and Lanelet B are `same_direction` if A and B are directly or indirectly `adjacent` to each other. | In each map, orange Lanelets are `same_dirction` as green Lanelet.
![same_direction](./media/nomenclature/same_direction.drawio.svg) | -| `bundle` | A `bundle` refers to a transitive closure set of Lanelets which are `same_direction` to each other. | The enclosed sets of Lanelets are `bundle`s.
![bundle](./media/nomenclature/bundle.drawio.svg) | -| `opposite` | If A is `opposite` to B, A and B share a common `boundary` with opposite direction. | In the first map, green Lanelet and orange Lanelet are `opposite` to each other.
In the second map, two red Lanelets are not `opposite` relation because they do not share a common LineString.
![opposite](./media/nomenclature/opposite.drawio.svg) | -| `opposite_direction` | If A and B are `opposite_direction`, the bundle of A and B are directly `opposite` to each other. | In the each map, green Lanelet and orange Lanelet are `opposite_direction` becauase their `bundle`s(enclosed in dotted line) are `opposite` relation.
![opposite_direction](./media/nomenclature/opposite_direction.drawio.svg) | -| `connected` | A is `connected` to(from) B if and only if the `exit`(`entry`) of A is identical to the `entry`(`exit`) of B. | A is connected to B, and B is connected from A.
![connected](./media/nomenclature/connected.drawio.svg) | -| `following` | The `following` Lanelets of A is the list of Lanelets to which A is `connected`. | In each map, orange Lanelets are the `following` of green Lanelet.
![following](./media/nomenclature/following.drawio.svg) | -| `previous` | The `previous` Lanelets of A is the list of Lanelets from which A is `connected`. | In each map, orange Lanelets are the `previous` of green Lanelet.
![previous](./media/nomenclature/previous.drawio.svg) | -| `conflicting` | A is `conflicting` with B if A and B are geometrically intersecting. | | -| `merging` | A is said to be `merging` Lanelet of B if and only if A is `conflicting` with B and both A and B are connected to a common Lanelet. | In each map, one of the orange Lanelet is a `mergin` Lanelet of the other orange Lanelet.
![merging](./media/nomenclature/merging.drawio.svg) | -| `sibling` | The designated Lanelets are refered to as `sibling` if all of them are `connected` from a common Lanelet. | In each map, orange Lanelets are `sibling`s.
![sibling](./media/nomenclature/sibling.drawio.svg) | -| `oncoming` | TBD | TBD | -| `upcoming` | TBD | TBD | -| `sequence` | `sequence` is a list of Lanelets whose each element is `connected from` or `adjacent to` the previous element. | ![sequence](./media/nomenclature/sequence.drawio.svg) | +This package aims to strictly define the meaning of several words to clarify the documentation and API's scope. In the table below, `codespace` words are given specific meanings when used in the API and API description. _italic_ words are emphasized to indicate that it refers to social common sense which often comes with ambiguity. To help disambiguate the meaning, illustration is provided. "Lanelet" refers to the entity of a`lanelet::ConstLanelet` object in order to distinguish with the word "lane" used in social customs. `A` and `B` stands for some Lanelets objects. + +| Word | Meaning | Illustration | +| :-------------------------------- | :---------------------------------------------------------------------------------------------------------------------------------: | :---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------: | +| `driving` | The vehicle position belongs to the designated Lanelet. | In each map, green Lanelet are the `driving` lanes of the vehicle.
![driving](./media/nomenclature/driving.drawio.svg) | +| `boundary`,
`entry`,
`exit` | The `boundary` of a Lanelet refers to the left or right Linestring. | ![boundary_entry_exit](./media/nomenclature/boundary_entry_exit.drawio.svg) | +| `adjacent` | If A is `adjacent` to B, A and B share a common `boundary` with same direction either on the left or right side. | In each map, orange Lanelet is `adjacent` to green Lanelet.
![adjacent](./media/nomenclature/adjacent.drawio.svg) | +| `same_direction` | Lanelet A and Lanelet B are `same_direction` if A and B are directly or indirectly `adjacent` to each other. | In each map, orange Lanelets are `same_direction` as green Lanelet.
![same_direction](./media/nomenclature/same_direction.drawio.svg) | +| `bundle` | A `bundle` refers to a transitive closure set of Lanelets which are `same_direction` to each other. | The enclosed sets of Lanelets are `bundle`s.
![bundle](./media/nomenclature/bundle.drawio.svg) | +| `opposite` | If A is `opposite` to B, A and B share a common `boundary` with opposite direction. | In the first map, green Lanelet and orange Lanelet are `opposite` to each other.
In the second map, two red Lanelets are not `opposite` relation because they do not share a common LineString.
![opposite](./media/nomenclature/opposite.drawio.svg) | +| `opposite_direction` | If A and B are `opposite_direction`, the `bundle` of A and B are directly `opposite` to each other. | In the each map, green Lanelet and orange Lanelet are `opposite_direction` because their `bundle`s(enclosed in dotted line) are `opposite` relation.
![opposite_direction](./media/nomenclature/opposite_direction.drawio.svg) | +| `connected` | A is `connected` to(from) B if and only if the `exit`(`entry`) of A is identical to the `entry`(`exit`) of B. | A is connected to B, and B is connected from A.
![connected](./media/nomenclature/connected.drawio.svg) | +| `following` | The `following` Lanelets of A is the list of Lanelets to which A is `connected`. | In each map, orange Lanelets are the `following` of green Lanelet.
![following](./media/nomenclature/following.drawio.svg) | +| `previous` | The `previous` Lanelets of A is the list of Lanelets from which A is `connected`. | In each map, orange Lanelets are the `previous` of green Lanelet.
![previous](./media/nomenclature/previous.drawio.svg) | +| `conflicting` | A is `conflicting` with B if A and B are geometrically intersecting. | | +| `merging` | A is said to be `merging` Lanelet of B if and only if A is `conflicting` with B and both A and B are connected to a common Lanelet. | In each map, one of the orange Lanelet is a `merging` Lanelet of the other orange Lanelet.
![merging](./media/nomenclature/merging.drawio.svg) | +| `sibling` | The designated Lanelets are referred to as `sibling` if all of them are `connected` from a common Lanelet. | In each map, orange Lanelets are `sibling`s.
![sibling](./media/nomenclature/sibling.drawio.svg) | +| `oncoming` | TBD | TBD | +| `upcoming` | TBD | TBD | +| `sequence` | `sequence` is a list of Lanelets whose each element is `connected from` or `adjacent to` the previous element. | ![sequence](./media/nomenclature/sequence.drawio.svg) | ## API description +| Header | function | description | average computational complexity | illustration | +| :----------------------------------------- | ------------------------ | ------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `` | `is_road_lane` | | $O(1)$ | | +| | `is_shoulder_lane` | | $O(1)$ | | +| | `is_bicycle_lane` | | $O(1)$ | | +| `` | `left_lanelet` | This function ignores the permission of lane change. Also it ignores `shoulder` and `bicycle` Lanelet. | $O(1)$ | In the first map, the green Lanelet is the `left_lanelet` of the orange Lanelet.
In the second and third map, the `left_lanelet` of the orange Lanelet is `null`.
![left_lanelet](./media/api/left_lanelet.drawio.svg) | +| | `right_lanelet` | same as above `left_lanelet` | $O(1)$ | | +| | `left_opposite_lanelet` | same as below `right_opposite_lanelet` | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | | +| | `right_opposite_lanelet` | | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | In the first and second map, the green Lanelet is the `right_opposite_lanelet` of the orange Lanelet.
In the third map, the `right_opposite_lanelet` of the orange Lanelet is `null`.
![right_opposite_lanelet](./media/api/right_opposite_lanelet.drawio.svg) | +| | `leftmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first and second map, the green Lanelet is the `leftmost_lanelet` of the orange Lanelet.
In the third map, the `leftmost_lanelet` of the orange Lanelet is `null`.
![leftmost_lanelet](./media/api/leftmost_lanelet.drawio.svg) | +| | `rightmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelet is the `rightmost_lanelet` of the orange Lanelet.
In the second and third map, the `rightmost_lanelet` of the orange Lanelet is `null`.
![rightmost_lanelet](./media/api/rightmost_lanelet.drawio.svg) | +| | `left_lanelets` | The input Lanelet is not included in the output. | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelete are the `left_lanelets` of the orange Lanelet.
In the second and third map, `left_lanelets` of the orange Lanelet is empty.
![left_lanelets](./media/api/left_lanelets.drawio.svg) | +| | `right_lanelets` | same as above `left_lanelets`. | $O(W)$ where $W$ is the size of the `bundle.` | In the first map, the green Lanelets are the `right_lanelets` of the orange Lanelet.
In the second and third map, `right_lanelets` of the orange Lanelet is empty.
![right_lanelets](./media/api/right_lanelets.drawio.svg) | + +### complexity of `findUsage` + +The readers should be noted that following description is implementation dependent. + +- [LaneletMap.h](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/blob/d9320cf66698004cd5e57988ac001e02e73e2e40/lanelet2_core/include/lanelet2_core/LaneletMap.h) +- [LaneletMap.cpp](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/blob/d9320cf66698004cd5e57988ac001e02e73e2e40/lanelet2_core/src/LaneletMap.cpp) + +Lanelet map primitives(like `Lanelet`, `Area`, `RegulatoryElement`) are stored in several `PrimitiveLayer` objects according to their types as shown below. + +```cpp title="lanelet2_core/LaneletMap.h#L375-L438" +class LaneletMap : public LaneletMapLayers { + public: + using LaneletMapLayers::LaneletMapLayers; + <...> +}; +``` + +```cpp title="lanelet2_core/LaneletMap.h#L313-L359" +class LaneletMapLayers { + <...> + LaneletLayer laneletLayer; //!< access to the lanelets within this map + AreaLayer areaLayer; //!< access to areas + RegulatoryElementLayer regulatoryElementLayer; //!< access to regElems + PolygonLayer polygonLayer; //!< access to the polygons + LineStringLayer lineStringLayer; //!< access to the lineStrings + PointLayer pointLayer; //!< access to the points +}; +``` + +```cpp title="lanelet2_core/LaneletMap.h#L285-L303" +class LaneletLayer : public PrimitiveLayer { + public: + using PrimitiveLayer::findUsages; + LaneletLayer() = default; + ~LaneletLayer() = default; + LaneletLayer(const LaneletLayer&) = delete; + LaneletLayer operator=(LaneletLayer&) = delete; + Lanelets findUsages(const RegulatoryElementConstPtr& regElem); + ConstLanelets findUsages(const RegulatoryElementConstPtr& regElem) const; + <...> +}; +``` + +Each `PrimitiveLayer` owns a field named `tree_` that contains a lookup table named `usage` of type `UsageLookup`, + +```cpp title="lanelet2_core/LaneletMap.h#L38-L253" +template +class PrimitiveLayer { + public: + <...> + /** + * @brief finds usages of an owned type within this layer + * + * This is the non-const version to find usages of a primitive in a layer. + */ + std::vector findUsages(const traits::ConstPrimitiveType>& primitive); + <...> + struct Tree; + // NOLINTNEXTLINE + std::unique_ptr tree_; //!< Hides boost trees from you/the compiler +``` + +```cpp title="lanelet2_core/src/LaneletMap.cpp#L277-L308" +template +struct PrimitiveLayer::Tree { + using TreeNode = std::pair; + using RTree = bgi::rtree>; + static TreeNode treeNode(const T& elem) { return {geometry::boundingBox2d(to2D(elem)), elem}; } + <...> + RTree rTree; + UsageLookup usage; +}; +``` + +and `UsageLookup` contains reference relation between different types as `std::unordered_multimap`. + +```cpp title="lanelet2_core/src/LaneletMap.cpp#L259-L270" +template <> +struct UsageLookup { + void add(Lanelet ll) { + ownedLookup.insert(std::make_pair(ll.leftBound(), ll)); + ownedLookup.insert(std::make_pair(ll.rightBound(), ll)); + for (const auto& elem : ll.regulatoryElements()) { + regElemLookup.insert(std::make_pair(elem, ll)); + } + } + std::unordered_multimap ownedLookup; + std::unordered_multimap regElemLookup; +}; +``` + +Thus the complexity of `findUsage` function is equal to that of `std::unordered_multimap::equal_range` + +```cpp title="lanelet2_core/src/LaneletMap.cpp#L419-L424" +template +std::vector::ConstPrimitiveT> PrimitiveLayer::findUsages( + const traits::ConstPrimitiveType::PrimitiveT>>& primitive) const { + return forEachMatchInMultiMap::PrimitiveT>>( + tree_->usage.ownedLookup, primitive, [](const auto& elem) { return traits::toConst(elem.second); }); +} +``` + +```cpp title="lanelet2_core/src/LaneletMap.cpp#L165-L169" +template +std::vector forEachMatchInMultiMap(const MapT& map, const KeyT& key, Func&& f) { + auto range = map.equal_range(key); + return utils::transform(range.first, range.second, f); +} +``` + ## How to craft test map On the VMB, create the map in local projector(or convert it to local projector from MGRS projector) and save the file as ``. Next, select the point to use as (0.0, 0.0) and pass its `` and run diff --git a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/kind.hpp b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/kind.hpp index 1d5225ff4..974a5623d 100644 --- a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/kind.hpp +++ b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/kind.hpp @@ -19,9 +19,6 @@ namespace autoware::lanelet2_utility { - -inline namespace kind -{ static constexpr const char * k_road_lane_type = "road"; static constexpr const char * k_shoulder_lane_type = "road_shoulder"; static constexpr const char * k_bicycle_lane_type = "bicycle_lane"; @@ -58,10 +55,8 @@ bool is_shoulder_lane(const lanelet::ConstLanelet & lanelet); /** * @brief check if the given lanelet type has "bicycle_lane" subtype * @param [in] lanelet input lanelet - * @return if the lanelet is bicicye_lane or not + * @return if the lanelet is bicycle_lane or not */ bool is_bicycle_lane(const lanelet::ConstLanelet & lanelet); -} // namespace kind - } // namespace autoware::lanelet2_utility #endif // AUTOWARE_LANELET2_UTILITY__KIND_HPP_ diff --git a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp new file mode 100644 index 000000000..e94154e89 --- /dev/null +++ b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp @@ -0,0 +1,149 @@ +// Copyright 2025 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_UTILITY__TOPOLOGY_HPP_ +#define AUTOWARE_LANELET2_UTILITY__TOPOLOGY_HPP_ + +#include +#include + +#include +#include + +namespace autoware::lanelet2_utility +{ +/** + * @brief get the left adjacent and same_direction lanelet on the routing graph if exists regardless + * of lane change permission + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @return optional of left adjacent lanelet(nullopt if there is no such adjacent lanelet) + */ +std::optional left_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +/** + * @brief get the right adjacent and same_direction lanelet on the routing graph if exists + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @return optional of right adjacent lanelet(nullopt if there is no such adjacent lanelet) + */ +std::optional right_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +/** + * @brief get the left adjacent and opposite_direction lanelet on the routing graph if exists + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @return optional of the left opposite lanelet(nullopt if there is not such opposite lanelet) + */ +std::optional left_opposite_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +/** + * @brief get the right adjacent and opposite_direction lanelet on the routing graph if exists + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @return optional of the right opposite lanelet(nullopt if there is no such opposite lanelet) + */ +std::optional right_opposite_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +/** + * @brief get the leftmost same_direction lanelet if exists + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @return optional of such lanelet(nullopt if there is no such adjacent lanelet) + */ +std::optional leftmost_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +std::optional rightmost_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +/** + * @brief get the left lanelets which are adjacent to `lanelet` + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @param [in] include_opposite flag if opposite_direction lanelet is included + * @param [in] invert_opposite_lanelet flag if the opposite lanelet in the output is `.inverted()` + * or not + * @return the list of lanelets excluding `lanelet` which is ordered in the *hopping* number from + * `lanelet` + */ +lanelet::ConstLanelets left_lanelets( + const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph, + const bool include_opposite = false, const bool invert_opposite_lane = false); + +/** + * @brief get the right lanelets which are adjacent to `lanelet` + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @param [in] include_opposite flag if opposite_direction lanelet is included + * @param [in] invert_opposite_lanelet flag if the opposite lanelet in the output is `.inverted()` + * or not + * @return the list of lanelets excluding `lanelet` which is ordered in the *hopping* number from + * `lanelet` + */ +lanelet::ConstLanelets right_lanelets( + const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph, + const bool include_opposite = false, const bool invert_opposite_lane = false); + +/** + * @brief get the following lanelets + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @return the following lanelets + */ +lanelet::ConstLanelets following_lanelets( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +/** + * @brief get the previous lanelets + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @return the previous lanelets + */ +lanelet::ConstLanelets previous_lanelets( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +/** + * @brief get the sibling lanelets + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @return the sibling lanelets + */ +lanelet::ConstLanelets sibling_lanelets( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +/** + * @brief get Lanelet instances of the designated ids + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @return the list of Lanelets in the same order as `ids` + */ +lanelet::ConstLanelets from_ids( + const lanelet::LaneletMapConstPtr lanelet_map_ptr, const std::vector & ids); +} // namespace autoware::lanelet2_utility + +#endif // AUTOWARE_LANELET2_UTILITY__TOPOLOGY_HPP_ diff --git a/common/autoware_lanelet2_utility/media/api/left_lanelet.drawio.svg b/common/autoware_lanelet2_utility/media/api/left_lanelet.drawio.svg new file mode 100644 index 000000000..4d61a038c --- /dev/null +++ b/common/autoware_lanelet2_utility/media/api/left_lanelet.drawio.svg @@ -0,0 +1,648 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + shoulder lane + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + bicycle lane + + + + + + +
+
+
+ + (1) + +
+
+
+
+ (1) +
+
+ + + + +
+
+
+ + (2) + +
+
+
+
+ (2) +
+
+ + + + +
+
+
+ + (3) + +
+
+
+
+ (3) +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/common/autoware_lanelet2_utility/media/api/left_lanelets.drawio.svg b/common/autoware_lanelet2_utility/media/api/left_lanelets.drawio.svg new file mode 100644 index 000000000..64edd454c --- /dev/null +++ b/common/autoware_lanelet2_utility/media/api/left_lanelets.drawio.svg @@ -0,0 +1,672 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + shoulder lane + + + + + + + bicycle lane + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 2 +
+
+
+
+ 2 +
+
+ + + + +
+
+
+ + (3) + +
+
+
+
+ (3) +
+
+ + + + +
+
+
+ + (1) + +
+
+
+
+ (1) +
+
+ + + + +
+
+
+ + (2) + +
+
+
+
+ (2) +
+
+ + + + + +
+
+
+ 1 +
+
+
+
+ 1 +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/common/autoware_lanelet2_utility/media/api/leftmost_lanelet.drawio.svg b/common/autoware_lanelet2_utility/media/api/leftmost_lanelet.drawio.svg new file mode 100644 index 000000000..3b046687e --- /dev/null +++ b/common/autoware_lanelet2_utility/media/api/leftmost_lanelet.drawio.svg @@ -0,0 +1,629 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + shoulder lane + + + + + + + bicycle lane + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + (1) + +
+
+
+
+ (1) +
+
+ + + + +
+
+
+ + (2) + +
+
+
+
+ (2) +
+
+ + + + +
+
+
+ + (3) + +
+
+
+
+ (3) +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/common/autoware_lanelet2_utility/media/api/right_lanelets.drawio.svg b/common/autoware_lanelet2_utility/media/api/right_lanelets.drawio.svg new file mode 100644 index 000000000..9d6b78f37 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/api/right_lanelets.drawio.svg @@ -0,0 +1,470 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + bicycle lane + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 2 +
+
+
+
+ 2 +
+
+ + + + +
+
+
+ + (1) + +
+
+
+
+ (1) +
+
+ + + + +
+
+
+ + (2) + +
+
+
+
+ (2) +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + (3) + +
+
+
+
+ (3) +
+
+ + + + +
+
+
+ 1 +
+
+
+
+ 1 +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/common/autoware_lanelet2_utility/media/api/right_opposite_lanelet.drawio.svg b/common/autoware_lanelet2_utility/media/api/right_opposite_lanelet.drawio.svg new file mode 100644 index 000000000..98c63bf58 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/api/right_opposite_lanelet.drawio.svg @@ -0,0 +1,640 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + shoulder lane + + + + + + + bicycle lane + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + (1) + +
+
+
+
+ (1) +
+
+ + + + +
+
+
+ + (2) + +
+
+
+
+ (2) +
+
+ + + + +
+
+
+ + (3) + +
+
+
+
+ (3) +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/common/autoware_lanelet2_utility/media/api/rightmost_lanelet.drawio.svg b/common/autoware_lanelet2_utility/media/api/rightmost_lanelet.drawio.svg new file mode 100644 index 000000000..02bece1c1 --- /dev/null +++ b/common/autoware_lanelet2_utility/media/api/rightmost_lanelet.drawio.svg @@ -0,0 +1,435 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + bicycle lane + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + (1) + +
+
+
+
+ (1) +
+
+ + + + +
+
+
+ + (2) + +
+
+
+
+ (2) +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + (3) + +
+
+
+
+ (3) +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/common/autoware_lanelet2_utility/src/kind.cpp b/common/autoware_lanelet2_utility/src/kind.cpp index 12a6e98e1..d369a22ef 100644 --- a/common/autoware_lanelet2_utility/src/kind.cpp +++ b/common/autoware_lanelet2_utility/src/kind.cpp @@ -18,9 +18,6 @@ namespace autoware::lanelet2_utility { - -inline namespace kind -{ bool is_road_lane(const lanelet::ConstLanelet & lanelet) { return strcmp(lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_road_lane_type) == @@ -38,5 +35,4 @@ bool is_bicycle_lane(const lanelet::ConstLanelet & lanelet) return strcmp( lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_bicycle_lane_type) == 0; } -} // namespace kind } // namespace autoware::lanelet2_utility diff --git a/common/autoware_lanelet2_utility/src/topology.cpp b/common/autoware_lanelet2_utility/src/topology.cpp new file mode 100644 index 000000000..6569999cc --- /dev/null +++ b/common/autoware_lanelet2_utility/src/topology.cpp @@ -0,0 +1,70 @@ +// Copyright 2025 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 + +#include +#include + +#include + +namespace autoware::lanelet2_utility +{ +std::optional left_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +std::optional right_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +std::optional left_opposite_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +std::optional right_opposite_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +std::optional leftmost_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +std::optional rightmost_lanelet( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +lanelet::ConstLanelets left_lanelets( + const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph, + const bool include_opposite, const bool invert_opposite_lane); + +lanelet::ConstLanelets right_lanelets( + const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph, + const bool include_opposite, const bool invert_opposite_lane); + +lanelet::ConstLanelets following_lanelets( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +lanelet::ConstLanelets previous_lanelets( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +lanelet::ConstLanelets sibling_lanelets( + const lanelet::ConstLanelet & lanelet, + const lanelet::routing::RoutingGraphConstPtr routing_graph); + +lanelet::ConstLanelets from_ids( + const lanelet::LaneletMapConstPtr lanelet_map_ptr, const std::vector & ids); +} // namespace autoware::lanelet2_utility From d043752943e25510d538bdb7d23842c1fd03f19a Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 3 Mar 2025 07:31:33 +0900 Subject: [PATCH 03/17] rename script Signed-off-by: Mamoru Sobue --- common/autoware_lanelet2_utility/CMakeLists.txt | 2 +- common/autoware_lanelet2_utility/README.md | 2 +- .../{lanelet_anonymization_local.py => lanelet_anonymizer.py} | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename common/autoware_lanelet2_utility/scripts/{lanelet_anonymization_local.py => lanelet_anonymizer.py} (100%) diff --git a/common/autoware_lanelet2_utility/CMakeLists.txt b/common/autoware_lanelet2_utility/CMakeLists.txt index da576dc0b..3d3ce5ae6 100644 --- a/common/autoware_lanelet2_utility/CMakeLists.txt +++ b/common/autoware_lanelet2_utility/CMakeLists.txt @@ -28,6 +28,6 @@ ament_auto_package(INSTALL_TO_SHARE ) install(PROGRAMS - scripts/lanelet_anonymization_local.py + scripts/lanelet_anonymizer.py DESTINATION lib/${PROJECT_NAME} ) diff --git a/common/autoware_lanelet2_utility/README.md b/common/autoware_lanelet2_utility/README.md index 2c2955a3f..644f6862c 100644 --- a/common/autoware_lanelet2_utility/README.md +++ b/common/autoware_lanelet2_utility/README.md @@ -154,7 +154,7 @@ std::vector forEachMatchInMultiMap(const MapT& map, const KeyT& key, Func&& f On the VMB, create the map in local projector(or convert it to local projector from MGRS projector) and save the file as ``. Next, select the point to use as (0.0, 0.0) and pass its `` and run ```bash -ros2 run autoware_lanelet2_utility lanelet_anonymization_local.py +ros2 run autoware_lanelet2_utility lanelet_anonymizer.py ``` Then the coordinate of the specified point is (0, 0) on the loaded map diff --git a/common/autoware_lanelet2_utility/scripts/lanelet_anonymization_local.py b/common/autoware_lanelet2_utility/scripts/lanelet_anonymizer.py similarity index 100% rename from common/autoware_lanelet2_utility/scripts/lanelet_anonymization_local.py rename to common/autoware_lanelet2_utility/scripts/lanelet_anonymizer.py From 421c858a5b7dffdc63d5872f261e77fc43dfb05d Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 4 Mar 2025 22:42:11 +0900 Subject: [PATCH 04/17] added topology Signed-off-by: Mamoru Sobue --- .../autoware_lanelet2_utility/CMakeLists.txt | 1 + common/autoware_lanelet2_utility/README.md | 71 +++--- .../autoware_lanelet2_utility/topology.hpp | 46 +++- common/autoware_lanelet2_utility/package.xml | 1 + .../src/topology.cpp | 227 ++++++++++++++++-- 5 files changed, 281 insertions(+), 65 deletions(-) diff --git a/common/autoware_lanelet2_utility/CMakeLists.txt b/common/autoware_lanelet2_utility/CMakeLists.txt index 3d3ce5ae6..4d964937c 100644 --- a/common/autoware_lanelet2_utility/CMakeLists.txt +++ b/common/autoware_lanelet2_utility/CMakeLists.txt @@ -6,6 +6,7 @@ autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED src/kind.cpp + src/topology.cpp ) if(BUILD_TESTING) diff --git a/common/autoware_lanelet2_utility/README.md b/common/autoware_lanelet2_utility/README.md index 644f6862c..4d2499e3e 100644 --- a/common/autoware_lanelet2_utility/README.md +++ b/common/autoware_lanelet2_utility/README.md @@ -4,40 +4,47 @@ This package aims to strictly define the meaning of several words to clarify the documentation and API's scope. In the table below, `codespace` words are given specific meanings when used in the API and API description. _italic_ words are emphasized to indicate that it refers to social common sense which often comes with ambiguity. To help disambiguate the meaning, illustration is provided. "Lanelet" refers to the entity of a`lanelet::ConstLanelet` object in order to distinguish with the word "lane" used in social customs. `A` and `B` stands for some Lanelets objects. -| Word | Meaning | Illustration | -| :-------------------------------- | :---------------------------------------------------------------------------------------------------------------------------------: | :---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------: | -| `driving` | The vehicle position belongs to the designated Lanelet. | In each map, green Lanelet are the `driving` lanes of the vehicle.
![driving](./media/nomenclature/driving.drawio.svg) | -| `boundary`,
`entry`,
`exit` | The `boundary` of a Lanelet refers to the left or right Linestring. | ![boundary_entry_exit](./media/nomenclature/boundary_entry_exit.drawio.svg) | -| `adjacent` | If A is `adjacent` to B, A and B share a common `boundary` with same direction either on the left or right side. | In each map, orange Lanelet is `adjacent` to green Lanelet.
![adjacent](./media/nomenclature/adjacent.drawio.svg) | -| `same_direction` | Lanelet A and Lanelet B are `same_direction` if A and B are directly or indirectly `adjacent` to each other. | In each map, orange Lanelets are `same_direction` as green Lanelet.
![same_direction](./media/nomenclature/same_direction.drawio.svg) | -| `bundle` | A `bundle` refers to a transitive closure set of Lanelets which are `same_direction` to each other. | The enclosed sets of Lanelets are `bundle`s.
![bundle](./media/nomenclature/bundle.drawio.svg) | -| `opposite` | If A is `opposite` to B, A and B share a common `boundary` with opposite direction. | In the first map, green Lanelet and orange Lanelet are `opposite` to each other.
In the second map, two red Lanelets are not `opposite` relation because they do not share a common LineString.
![opposite](./media/nomenclature/opposite.drawio.svg) | -| `opposite_direction` | If A and B are `opposite_direction`, the `bundle` of A and B are directly `opposite` to each other. | In the each map, green Lanelet and orange Lanelet are `opposite_direction` because their `bundle`s(enclosed in dotted line) are `opposite` relation.
![opposite_direction](./media/nomenclature/opposite_direction.drawio.svg) | -| `connected` | A is `connected` to(from) B if and only if the `exit`(`entry`) of A is identical to the `entry`(`exit`) of B. | A is connected to B, and B is connected from A.
![connected](./media/nomenclature/connected.drawio.svg) | -| `following` | The `following` Lanelets of A is the list of Lanelets to which A is `connected`. | In each map, orange Lanelets are the `following` of green Lanelet.
![following](./media/nomenclature/following.drawio.svg) | -| `previous` | The `previous` Lanelets of A is the list of Lanelets from which A is `connected`. | In each map, orange Lanelets are the `previous` of green Lanelet.
![previous](./media/nomenclature/previous.drawio.svg) | -| `conflicting` | A is `conflicting` with B if A and B are geometrically intersecting. | | -| `merging` | A is said to be `merging` Lanelet of B if and only if A is `conflicting` with B and both A and B are connected to a common Lanelet. | In each map, one of the orange Lanelet is a `merging` Lanelet of the other orange Lanelet.
![merging](./media/nomenclature/merging.drawio.svg) | -| `sibling` | The designated Lanelets are referred to as `sibling` if all of them are `connected` from a common Lanelet. | In each map, orange Lanelets are `sibling`s.
![sibling](./media/nomenclature/sibling.drawio.svg) | -| `oncoming` | TBD | TBD | -| `upcoming` | TBD | TBD | -| `sequence` | `sequence` is a list of Lanelets whose each element is `connected from` or `adjacent to` the previous element. | ![sequence](./media/nomenclature/sequence.drawio.svg) | +| Word | Meaning | Illustration | +| --------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `driving` | The vehicle position belongs to the designated Lanelet. | In each map, green Lanelet are the `driving` lanes of the vehicle.
![driving](./media/nomenclature/driving.drawio.svg) | +| `boundary`,
`entry`,
`exit` | The `boundary` of a Lanelet refers to the left or right Linestring. | ![boundary_entry_exit](./media/nomenclature/boundary_entry_exit.drawio.svg) | +| `adjacent` | If A is `adjacent` to B, A and B share a common `boundary` with same direction either on the left or right side. | In each map, orange Lanelet is `adjacent` to green Lanelet.
![adjacent](./media/nomenclature/adjacent.drawio.svg) | +| `same_direction` | Lanelet A and Lanelet B are `same_direction` if A and B are directly or indirectly `adjacent` to each other. | In each map, orange Lanelets are `same_direction` as green Lanelet.
![same_direction](./media/nomenclature/same_direction.drawio.svg) | +| `bundle` | A `bundle` refers to a transitive closure set of Lanelets which are `same_direction` to each other. | The enclosed sets of Lanelets are `bundle`s.
![bundle](./media/nomenclature/bundle.drawio.svg) | +| `opposite` | If A is `opposite` to B, A and B share a common `boundary` with opposite direction. | In the first map, green Lanelet and orange Lanelet are `opposite` to each other.
In the second map, two red Lanelets are not `opposite` relation because they do not share a common LineString.
![opposite](./media/nomenclature/opposite.drawio.svg) | +| `opposite_direction` | If A and B are `opposite_direction`, the `bundle` of A and B are directly `opposite` to each other. | In the each map, green Lanelet and orange Lanelet are `opposite_direction` because their `bundle`s(enclosed in dotted line) are `opposite` relation.
![opposite_direction](./media/nomenclature/opposite_direction.drawio.svg) | +| `connected` | A is `connected` to(from) B if and only if the `exit`(`entry`) of A is identical to the `entry`(`exit`) of B. | A is connected to B, and B is connected from A.
![connected](./media/nomenclature/connected.drawio.svg) | +| `following` | The `following` Lanelets of A is the list of Lanelets to which A is `connected`. | In each map, orange Lanelets are the `following` of green Lanelet.
![following](./media/nomenclature/following.drawio.svg) | +| `previous` | The `previous` Lanelets of A is the list of Lanelets from which A is `connected`. | In each map, orange Lanelets are the `previous` of green Lanelet.
![previous](./media/nomenclature/previous.drawio.svg) | +| `conflicting` | A is `conflicting` with B if A and B are geometrically intersecting. | | +| `merging` | A is said to be `merging` Lanelet of B if and only if A is `conflicting` with B and both A and B are connected to a common Lanelet. | In each map, one of the orange Lanelet is a `merging` Lanelet of the other orange Lanelet.
![merging](./media/nomenclature/merging.drawio.svg) | +| `sibling` | The designated Lanelets are referred to as `sibling` if all of them are `connected` from a common Lanelet. | In each map, orange Lanelets are `sibling`s.
![sibling](./media/nomenclature/sibling.drawio.svg) | +| `oncoming` | TBD | TBD | +| `upcoming` | TBD | TBD | +| `sequence` | `sequence` is a list of Lanelets whose each element is `connected from` or `adjacent to` the previous element. | ![sequence](./media/nomenclature/sequence.drawio.svg) | +| `similar` | A and B are called `similar` if and only if both of them have same valid `turn_direction` value. | | ## API description -| Header | function | description | average computational complexity | illustration | -| :----------------------------------------- | ------------------------ | ------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `` | `is_road_lane` | | $O(1)$ | | -| | `is_shoulder_lane` | | $O(1)$ | | -| | `is_bicycle_lane` | | $O(1)$ | | -| `` | `left_lanelet` | This function ignores the permission of lane change. Also it ignores `shoulder` and `bicycle` Lanelet. | $O(1)$ | In the first map, the green Lanelet is the `left_lanelet` of the orange Lanelet.
In the second and third map, the `left_lanelet` of the orange Lanelet is `null`.
![left_lanelet](./media/api/left_lanelet.drawio.svg) | -| | `right_lanelet` | same as above `left_lanelet` | $O(1)$ | | -| | `left_opposite_lanelet` | same as below `right_opposite_lanelet` | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | | -| | `right_opposite_lanelet` | | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | In the first and second map, the green Lanelet is the `right_opposite_lanelet` of the orange Lanelet.
In the third map, the `right_opposite_lanelet` of the orange Lanelet is `null`.
![right_opposite_lanelet](./media/api/right_opposite_lanelet.drawio.svg) | -| | `leftmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first and second map, the green Lanelet is the `leftmost_lanelet` of the orange Lanelet.
In the third map, the `leftmost_lanelet` of the orange Lanelet is `null`.
![leftmost_lanelet](./media/api/leftmost_lanelet.drawio.svg) | -| | `rightmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelet is the `rightmost_lanelet` of the orange Lanelet.
In the second and third map, the `rightmost_lanelet` of the orange Lanelet is `null`.
![rightmost_lanelet](./media/api/rightmost_lanelet.drawio.svg) | -| | `left_lanelets` | The input Lanelet is not included in the output. | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelete are the `left_lanelets` of the orange Lanelet.
In the second and third map, `left_lanelets` of the orange Lanelet is empty.
![left_lanelets](./media/api/left_lanelets.drawio.svg) | -| | `right_lanelets` | same as above `left_lanelets`. | $O(W)$ where $W$ is the size of the `bundle.` | In the first map, the green Lanelets are the `right_lanelets` of the orange Lanelet.
In the second and third map, `right_lanelets` of the orange Lanelet is empty.
![right_lanelets](./media/api/right_lanelets.drawio.svg) | +| Header | function | description | average computational complexity | illustration | +| ------------------------------------------ | ----------------------------- | ------------------------------------------------------------------------------------------------------ | ---------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `` | `is_road_lane` | | $O(1)$ | | +| | `is_shoulder_lane` | | $O(1)$ | | +| | `is_bicycle_lane` | | $O(1)$ | | +| `` | `left_lanelet` | This function ignores the permission of lane change. Also it ignores `shoulder` and `bicycle` Lanelet. | $O(1)$ | In the first map, the green Lanelet is the `left_lanelet` of the orange Lanelet.
In the second and third map, the `left_lanelet` of the orange Lanelet is `null`.
![left_lanelet](./media/api/left_lanelet.drawio.svg) | +| | `right_lanelet` | same as above `left_lanelet` | $O(1)$ | | +| | `left_similar_lanelet`(TODO) | same as above `left_lanelet` | $O(1)$ | | +| | `right_similar_lanelet`(TODO) | same as above `left_lanelet` | $O(1)$ | | +| | `left_opposite_lanelet` | same as below `right_opposite_lanelet` | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | | +| | `right_opposite_lanelet` | | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | In the first and second map, the green Lanelet is the `right_opposite_lanelet` of the orange Lanelet.
In the third map, the `right_opposite_lanelet` of the orange Lanelet is `null`.
![right_opposite_lanelet](./media/api/right_opposite_lanelet.drawio.svg) | +| | `leftmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first and second map, the green Lanelet is the `leftmost_lanelet` of the orange Lanelet.
In the third map, the `leftmost_lanelet` of the orange Lanelet is `null`.
![leftmost_lanelet](./media/api/leftmost_lanelet.drawio.svg) | +| | `rightmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelet is the `rightmost_lanelet` of the orange Lanelet.
In the second and third map, the `rightmost_lanelet` of the orange Lanelet is `null`.
![rightmost_lanelet](./media/api/rightmost_lanelet.drawio.svg) | +| | `left_lanelets` | The input Lanelet is not included in the output. | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelete are the `left_lanelets` of the orange Lanelet.
In the second and third map, `left_lanelets` of the orange Lanelet is empty.
![left_lanelets](./media/api/left_lanelets.drawio.svg) | +| | `right_lanelets` | same as above `left_lanelets`. | $O(W)$ where $W$ is the size of the `bundle.` | In the first map, the green Lanelets are the `right_lanelets` of the orange Lanelet.
In the second and third map, `right_lanelets` of the orange Lanelet is empty.
![right_lanelets](./media/api/right_lanelets.drawio.svg) | +| | `following_lanelets` | | $O(E)$ where $E$ is the number of Lanelets to which the input is connected to. | | +| | `previous_lanelets` | | $O(E)$ where $E$ is the number of Lanelets from which the input is connected from. | | +| | `sibling_lanelets` | | $O(E)$ where $E$ is the number of sibling Lanelets | | +| | `from_ids` | | $O(n)$ | | ### complexity of `findUsage` @@ -130,7 +137,7 @@ struct UsageLookup { }; ``` -Thus the complexity of `findUsage` function is equal to that of `std::unordered_multimap::equal_range` +Thus the complexity of `findUsage` function is equal to that of `std::unordered_multimap::equal_range` which is $O(1)$. ```cpp title="lanelet2_core/src/LaneletMap.cpp#L419-L424" template diff --git a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp index e94154e89..24ac75ca5 100644 --- a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp +++ b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp @@ -45,14 +45,39 @@ std::optional right_lanelet( const lanelet::routing::RoutingGraphConstPtr routing_graph); /** - * @brief get the left adjacent and opposite_direction lanelet on the routing graph if exists + * @brief get left_lanelet() or sibling lanelet. If `lanelet` has turn_direction, search for sibling + * lanelet is limited to the one with same turn_direction value + * @param [in] lanelet input lanelet + * @param [in] routing_graph routing_graph containing `lanelet` + * @return optional of abovementioned lanelet(nullopt if there is no such lanelet) + */ +/* +std::optional left_similar_lanelet( +const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map, +const lanelet::routing::RoutingGraphConstPtr routing_graph); +*/ + +/** + * @brief get right_lanelet() or sibling lanelet. If `lanelet` has turn_direction, search for + * sibling lanelet is limited to the one with same turn_direction value * @param [in] lanelet input lanelet * @param [in] routing_graph routing_graph containing `lanelet` + * @return optional of abovementioned lanelet(nullopt if there is no such lanelet) + */ +/* +std::optional right_similar_lanelet( +const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map, +const lanelet::routing::RoutingGraphConstPtr routing_graph); +*/ + +/** + * @brief get the left adjacent and opposite_direction lanelet on the routing graph if exists + * @param [in] lanelet input lanelet + * @param [in] lanelet_map lanelet_map containing `lanelet` * @return optional of the left opposite lanelet(nullopt if there is not such opposite lanelet) */ std::optional left_opposite_lanelet( - const lanelet::ConstLanelet & lanelet, - const lanelet::routing::RoutingGraphConstPtr routing_graph); + const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map); /** * @brief get the right adjacent and opposite_direction lanelet on the routing graph if exists @@ -61,8 +86,7 @@ std::optional left_opposite_lanelet( * @return optional of the right opposite lanelet(nullopt if there is no such opposite lanelet) */ std::optional right_opposite_lanelet( - const lanelet::ConstLanelet & lanelet, - const lanelet::routing::RoutingGraphConstPtr routing_graph); + const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map); /** * @brief get the leftmost same_direction lanelet if exists @@ -89,8 +113,9 @@ std::optional rightmost_lanelet( * `lanelet` */ lanelet::ConstLanelets left_lanelets( - const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph, - const bool include_opposite = false, const bool invert_opposite_lane = false); + const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map, + const lanelet::routing::RoutingGraphConstPtr routing_graph, const bool include_opposite = false, + const bool invert_opposite_lane = false); /** * @brief get the right lanelets which are adjacent to `lanelet` @@ -103,8 +128,9 @@ lanelet::ConstLanelets left_lanelets( * `lanelet` */ lanelet::ConstLanelets right_lanelets( - const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph, - const bool include_opposite = false, const bool invert_opposite_lane = false); + const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map, + const lanelet::routing::RoutingGraphConstPtr routing_graph, const bool include_opposite = false, + const bool invert_opposite_lane = false); /** * @brief get the following lanelets @@ -143,7 +169,7 @@ lanelet::ConstLanelets sibling_lanelets( * @return the list of Lanelets in the same order as `ids` */ lanelet::ConstLanelets from_ids( - const lanelet::LaneletMapConstPtr lanelet_map_ptr, const std::vector & ids); + const lanelet::LaneletMapConstPtr lanelet_map, const std::vector & ids); } // namespace autoware::lanelet2_utility #endif // AUTOWARE_LANELET2_UTILITY__TOPOLOGY_HPP_ diff --git a/common/autoware_lanelet2_utility/package.xml b/common/autoware_lanelet2_utility/package.xml index a7009db32..7ca1cbd52 100644 --- a/common/autoware_lanelet2_utility/package.xml +++ b/common/autoware_lanelet2_utility/package.xml @@ -13,6 +13,7 @@ autoware_cmake autoware_lanelet2_extension + rclcpp visualization_msgs ament_cmake_ros diff --git a/common/autoware_lanelet2_utility/src/topology.cpp b/common/autoware_lanelet2_utility/src/topology.cpp index 6569999cc..96d8c8b72 100644 --- a/common/autoware_lanelet2_utility/src/topology.cpp +++ b/common/autoware_lanelet2_utility/src/topology.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include @@ -21,50 +22,230 @@ namespace autoware::lanelet2_utility { + +static constexpr size_t k_normal_bundle_max_size = 10; + std::optional left_lanelet( - const lanelet::ConstLanelet & lanelet, - const lanelet::routing::RoutingGraphConstPtr routing_graph); + const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph) +{ + if (const auto left_lane = routing_graph->left(lanelet)) { + // lane changeable + return *left_lane; + } + if (const auto adjacent_left_lane = routing_graph->adjacentLeft(lanelet)) { + return *adjacent_left_lane; + } + return std::nullopt; +} std::optional right_lanelet( - const lanelet::ConstLanelet & lanelet, - const lanelet::routing::RoutingGraphConstPtr routing_graph); + const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph) +{ + if (const auto right_lane = routing_graph->right(lanelet)) { + // lane changeable + return *right_lane; + } + if (const auto adjacent_right_lane = routing_graph->adjacentRight(lanelet)) { + return *adjacent_right_lane; + } + return std::nullopt; +} + +/* +std::optional left_similar_lanelet( +const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map, +const lanelet::routing::RoutingGraphConstPtr routing_graph); +*/ + +/* +std::optional right_similar_lanelet( +const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map, +const lanelet::routing::RoutingGraphConstPtr routing_graph); +*/ std::optional left_opposite_lanelet( - const lanelet::ConstLanelet & lanelet, - const lanelet::routing::RoutingGraphConstPtr routing_graph); + const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map) +{ + for (const auto & opposite_candidate : + lanelet_map->laneletLayer.findUsages(lanelet.leftBound().invert())) { + if (opposite_candidate.rightBound().id() == lanelet.leftBound().id()) { + return opposite_candidate; + } + } + return std::nullopt; +} std::optional right_opposite_lanelet( - const lanelet::ConstLanelet & lanelet, - const lanelet::routing::RoutingGraphConstPtr routing_graph); + const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map) +{ + for (const auto & opposite_candidate : + lanelet_map->laneletLayer.findUsages(lanelet.rightBound().invert())) { + if (opposite_candidate.leftBound().id() == lanelet.rightBound().id()) { + return opposite_candidate; + } + } + return std::nullopt; +} std::optional leftmost_lanelet( - const lanelet::ConstLanelet & lanelet, - const lanelet::routing::RoutingGraphConstPtr routing_graph); + const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph) +{ + auto left_lane = left_lanelet(lanelet, routing_graph); + if (!left_lane) { + return std::nullopt; + } + size_t bundle_size_diagnosis = 0; + while (bundle_size_diagnosis < k_normal_bundle_max_size) { + const auto next_left_lane = left_lanelet(left_lane.value(), routing_graph); + if (!next_left_lane) { + // reached + return left_lane; + } + left_lane = next_left_lane.value(); + bundle_size_diagnosis++; + } + + RCLCPP_ERROR( + rclcpp::get_logger("autoware_lanelet2_utility"), + "You have passed an unrealistic map with a bundle of size>=10"); + return std::nullopt; +} std::optional rightmost_lanelet( - const lanelet::ConstLanelet & lanelet, - const lanelet::routing::RoutingGraphConstPtr routing_graph); + const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph) +{ + auto right_lane = right_lanelet(lanelet, routing_graph); + if (!right_lane) { + return std::nullopt; + } + size_t bundle_size_diagnosis = 0; + while (bundle_size_diagnosis < k_normal_bundle_max_size) { + const auto next_right_lane = left_lanelet(right_lane.value(), routing_graph); + if (!next_right_lane) { + // reached + return right_lane; + } + right_lane = next_right_lane.value(); + bundle_size_diagnosis++; + } + + RCLCPP_ERROR( + rclcpp::get_logger("autoware_lanelet2_utility"), + "You have passed an unrealistic map with a bundle of size>=10"); + return std::nullopt; +} lanelet::ConstLanelets left_lanelets( - const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph, - const bool include_opposite, const bool invert_opposite_lane); + const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map, + const lanelet::routing::RoutingGraphConstPtr routing_graph, const bool include_opposite, + const bool invert_opposite_lane) +{ + lanelet::ConstLanelets lefts{}; + auto left_lane = left_lanelet(lanelet, routing_graph); + size_t bundle_size_diagnosis = 0; + while (bundle_size_diagnosis < k_normal_bundle_max_size) { + if (!left_lane) { + break; + } + lefts.push_back(left_lane.value()); + left_lane = left_lanelet(left_lane.value(), routing_graph); + bundle_size_diagnosis++; + } + if (bundle_size_diagnosis >= k_normal_bundle_max_size) { + RCLCPP_ERROR( + rclcpp::get_logger("autoware_lanelet2_utility"), + "You have passed an unrealistic map with a bundle of size>=10"); + return {}; + } + if (lefts.empty()) { + return {}; + } + const auto & leftmost = lefts.back(); + if (include_opposite) { + const auto direct_opposite = right_opposite_lanelet(leftmost, lanelet_map); + if (direct_opposite) { + const auto opposites = + right_lanelets(direct_opposite.value(), lanelet_map, routing_graph, false, false); + for (const auto & opposite : opposites) { + lefts.push_back(invert_opposite_lane ? opposite.invert() : opposite); + } + } + } + return lefts; +} lanelet::ConstLanelets right_lanelets( - const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph, - const bool include_opposite, const bool invert_opposite_lane); + const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map, + const lanelet::routing::RoutingGraphConstPtr routing_graph, const bool include_opposite, + const bool invert_opposite_lane) +{ + lanelet::ConstLanelets rights{}; + auto right_lane = right_lanelet(lanelet, routing_graph); + size_t bundle_size_diagnosis = 0; + while (bundle_size_diagnosis < k_normal_bundle_max_size) { + if (!right_lane) { + break; + } + rights.push_back(right_lane.value()); + right_lane = right_lanelet(right_lane.value(), routing_graph); + bundle_size_diagnosis++; + } + if (bundle_size_diagnosis >= k_normal_bundle_max_size) { + RCLCPP_ERROR( + rclcpp::get_logger("autoware_lanelet2_utility"), + "You have passed an unrealistic map with a bundle of size>=10"); + return {}; + } + if (rights.empty()) { + return {}; + } + const auto & rightmost = rights.back(); + if (include_opposite) { + const auto direct_opposite = right_opposite_lanelet(rightmost, lanelet_map); + if (direct_opposite) { + const auto opposites = + left_lanelets(direct_opposite.value(), lanelet_map, routing_graph, false, false); + for (const auto & opposite : opposites) { + rights.push_back(invert_opposite_lane ? opposite.invert() : opposite); + } + } + } + return rights; +} lanelet::ConstLanelets following_lanelets( - const lanelet::ConstLanelet & lanelet, - const lanelet::routing::RoutingGraphConstPtr routing_graph); + const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph) +{ + return routing_graph->following(lanelet); +} lanelet::ConstLanelets previous_lanelets( - const lanelet::ConstLanelet & lanelet, - const lanelet::routing::RoutingGraphConstPtr routing_graph); + const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph) +{ + return routing_graph->previous(lanelet); +} lanelet::ConstLanelets sibling_lanelets( - const lanelet::ConstLanelet & lanelet, - const lanelet::routing::RoutingGraphConstPtr routing_graph); + const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph) +{ + lanelet::ConstLanelets siblings; + for (const auto & previous : previous_lanelets(lanelet, routing_graph)) { + for (const auto & following : following_lanelets(previous, routing_graph)) { + if (following.id() != lanelet.id()) { + siblings.push_back(following); + } + } + } + return siblings; +} lanelet::ConstLanelets from_ids( - const lanelet::LaneletMapConstPtr lanelet_map_ptr, const std::vector & ids); + const lanelet::LaneletMapConstPtr lanelet_map, const std::vector & ids) +{ + lanelet::ConstLanelets lanelets; + for (const auto id : ids) { + lanelets.push_back(lanelet_map->laneletLayer.get(id)); + } + return lanelets; +} } // namespace autoware::lanelet2_utility From c5bfb494bfeea9e401a30b79d7101d5489f30a39 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 5 Mar 2025 13:45:49 +0900 Subject: [PATCH 05/17] lanelet id aligner Signed-off-by: Mamoru Sobue --- .../scripts/lanelet_id_aligner.py | 72 +++++++++++++++++++ 1 file changed, 72 insertions(+) create mode 100755 common/autoware_lanelet2_utility/scripts/lanelet_id_aligner.py diff --git a/common/autoware_lanelet2_utility/scripts/lanelet_id_aligner.py b/common/autoware_lanelet2_utility/scripts/lanelet_id_aligner.py new file mode 100755 index 000000000..aa01ad8c2 --- /dev/null +++ b/common/autoware_lanelet2_utility/scripts/lanelet_id_aligner.py @@ -0,0 +1,72 @@ +#!/usr/bin/env python3 + +# Copyright 2025 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 argparse +import xml.etree.ElementTree as ET + + +def renumber_osm_ids(input_file): + tree = ET.parse(input_file) + root = tree.getroot() + + id_map = {} + new_id = 0 + + # Collect nodes, ways, and relations with new ids + for element in root.findall("node") + root.findall("way") + root.findall("relation"): + old_id = element.attrib["id"] + id_map[old_id] = str(new_id) + element.set("id", str(new_id)) + new_id += 1 + + # Update references in (inside ) and (inside ) + for way in root.findall("way"): + for nd in way.findall("nd"): + old_ref = nd.attrib["ref"] + if old_ref in id_map: + nd.set("ref", id_map[old_ref]) + else: + print(f"reference to ref={old_ref} was invalid") + + for relation in root.findall("relation"): + for member in relation.findall("member"): + old_ref = member.attrib["ref"] + if old_ref in id_map: + member.set("ref", id_map[old_ref]) + else: + print(f"reference to ref={old_ref} was invalid") + + for tag in relation.findall("tag"): + if tag.attrib["k"] != "intersection_area": + continue + + old_ref = tag.attrib["v"] + if old_ref in id_map: + tag.set("k", id_map[old_ref]) + else: + print(f"reference to ref={old_ref} was invalid") + + tree.write(input_file, encoding="utf-8", xml_declaration=True) + print(f"Updated OSM file {input_file}") + + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + description="Update OSM file with new origin and adjusted coordinates." + ) + parser.add_argument("input_osm", help="Path to the input OSM file") + args = parser.parse_args() + renumber_osm_ids(args.input_osm) From c14a20e70ee267494a30723094a7dacf4d8bdf31 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 5 Mar 2025 14:24:01 +0900 Subject: [PATCH 06/17] aligned lanelet maps, add crossing map Signed-off-by: Mamoru Sobue --- .../autoware_lanelet2_utility/CMakeLists.txt | 1 + common/autoware_lanelet2_utility/README.md | 18 +- .../media/maps/intersection/crossing.png | Bin 0 -> 199869 bytes .../media/maps/road_shoulder/highway.png | Bin 0 -> 33082 bytes .../media/maps/road_shoulder/pudo.png | Bin 0 -> 78476 bytes .../sample_map/intersection/crossing.osm | 15586 ++++++++++++++++ .../sample_map/road_shoulder/highway.osm | 232 +- .../sample_map/road_shoulder/pudo.osm | 1192 +- .../scripts/lanelet_id_aligner.py | 2 +- .../autoware_lanelet2_utility/test/kind.cpp | 10 +- 10 files changed, 16321 insertions(+), 720 deletions(-) create mode 100644 common/autoware_lanelet2_utility/media/maps/intersection/crossing.png create mode 100644 common/autoware_lanelet2_utility/media/maps/road_shoulder/highway.png create mode 100644 common/autoware_lanelet2_utility/media/maps/road_shoulder/pudo.png create mode 100644 common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm diff --git a/common/autoware_lanelet2_utility/CMakeLists.txt b/common/autoware_lanelet2_utility/CMakeLists.txt index 4d964937c..fb51b5792 100644 --- a/common/autoware_lanelet2_utility/CMakeLists.txt +++ b/common/autoware_lanelet2_utility/CMakeLists.txt @@ -30,5 +30,6 @@ ament_auto_package(INSTALL_TO_SHARE install(PROGRAMS scripts/lanelet_anonymizer.py + scripts/lanelet_id_aligner.py DESTINATION lib/${PROJECT_NAME} ) diff --git a/common/autoware_lanelet2_utility/README.md b/common/autoware_lanelet2_utility/README.md index 4d2499e3e..fa1c5d642 100644 --- a/common/autoware_lanelet2_utility/README.md +++ b/common/autoware_lanelet2_utility/README.md @@ -156,7 +156,15 @@ std::vector forEachMatchInMultiMap(const MapT& map, const KeyT& key, Func&& f } ``` -## How to craft test map +## Test maps + +| Map name | Origin point id | Image | +| --------------------------- | --------------- | --------------------------------------------------- | +| `road_shoulder/highway.osm` | `1` | ![highway](./media/maps/road_shoulder/highway.png) | +| `road_shoulder/pudo.osm` | `140` | ![pudo](./media/maps/road_shoulder/pudo.png) | +| `intersection/crossing.osm` | `1867` | ![crossing](./media/maps/intersection/crossing.png) | + +### How to craft test map On the VMB, create the map in local projector(or convert it to local projector from MGRS projector) and save the file as ``. Next, select the point to use as (0.0, 0.0) and pass its `` and run @@ -164,4 +172,10 @@ On the VMB, create the map in local projector(or convert it to local projector f ros2 run autoware_lanelet2_utility lanelet_anonymizer.py ``` -Then the coordinate of the specified point is (0, 0) on the loaded map +Then the coordinate of the specified point is (0, 0) on the loaded map. + +By applying `lanelet_id_aligner.py`, the primitive ids are aligned to start from 1 and increase one-by-one. + +```bash +ros2 run autoware_lanelet2_utility lanelet_id_aligner.py +``` diff --git a/common/autoware_lanelet2_utility/media/maps/intersection/crossing.png b/common/autoware_lanelet2_utility/media/maps/intersection/crossing.png new file mode 100644 index 0000000000000000000000000000000000000000..def5a0d22d60da10fbf97ca132daab0f4be05d6a GIT binary patch literal 199869 zcmeFZ`CC)T);3JHN9lHeK1W+nQM6@HQ9x0q2ytoz#GpV283dF`2ASt6*dC-+5J?1N z2vGqM5h5TnAt)k-QDy=JR00SDB4G$&NZzVs)8{!1C!0ld?AKIInp@ekiK24+8jSJ+Pue}TVu z`2Bvx&(zb&FYua=qnNXY=S{~WzV<$jjvl@@JpI_~sJfuh5!mRgkK;8z7f+A9W-d1! z#mpTY_Nt!Pd-0mj-eaoAPV7}Zrmd!?ef0R=OBeSVnwp7ET>V*0Y_FKXxzlDrX)MN2 zTpBlAWr6EcrgR8(51%~W!cvwWIj2Rnu$o@W-`3J|zCRZS8l}l5Lr5zeg5i z{l8oM|4x)dq*GCHR8-WuN_#X1O#G>TK1kdxoI*R5(b3UkM~}uQBqWf+DTA0jFXm=^ zP9*CW76y;C8vTLKF~qE#S2WQwp~XeaW$51igTQkwtl$;#OcN?cmj=dklZKX9o+A`$ zs7lXsbam)+D__j26Q^|#rn=~nb>*P>n_Yqtb06Oj?ck|a952ym zapj4BYn)*8g5V^9K;X5-k>{ks@>9}+Pg*P=;4O?)+wih!sl0C=jeUHVZg4)C;X)Ul zSmnqipjNDI-jwf|ww9jUQ{Gq!hZrfc;F_OONTk+*0qZ^`rSY(rOutH#wl?Ec&(dmv zmEbG7u{jk*E9EDh;pi+(Qqu*C@#i^j>t)B#+Y0wtpiO9_@eRgQWllY@*z$;)nwo{J zEt?%xKJGA~e=Qi?C6dqEstwmE=Gpl@&GW5jB5}!Rf@Vyzy}7bZtwf7V)sz{h#OVcWcvbVr15V9&ckryG`$t;m8fF zQuK1g`hjjSsw?eY+eYa>;SkywTM4(FTc$ ziG^?8m@TGE~p?oa8kzV8sCaz;>6By&ul;g`orny}{OLOB@bL|(x#|(Y7wPu4jENcNf zY$TT^D{yJAYDP7WlSXWUzAdm@RpjDyy9Lk}Yl?}SO61ero=M(PE_pOT&AH(LrxB|` zU@#o`67o-$yVCZ&h%9!_%VSKCQAd0+p&DAtCPIs)8q~cfq;e(zHZgu`lAo#rI8sfe8 zPbd;h>B(t^j^uSaV;xH3{rYNS=1o1*Q05;8NE2^1HA;ZyF>(7H#bLj~*MWPY&Q0BDYdY`Upd41XkQB#No>8T$d1bH*VWafY56KB zV$u$vVDx#7Oq}YyM6z5@Vk5@eoSddbAXArIC+0)wm&>v`3@mdUvq96yaAeTYmn#$A z^gCvk;p*cQ<4&fq_KfRnbGxpnRcIOj`;`8RBn^IuUTaZK+9F|U%B-Yx6EsxoUw;Ch z?l%iu3@isNErqi{!sj2DF?%{=Q zZ3DMr77U82$QnvJ#yTDAFI(k~=F$e{ycU|w37#jrlvIBmao8X1Bsp>bw2iFPw1i76 zCiX;Zwu{NSUKpkmT&gor4z`cKZ;%>#YTT)?BEj07v0Ow9X!np$m{~kJX5~rwV+Aiu z=?MiFe*R@g97#sl2b$eIei>C6sC@iHia|!gTt`y!vcsU^>ADx0Ni)}Tdv}Mve)Hy0 zR#sM_J!~JEDT>wmU7aUxv5YPbuAWs&t<{bk@~B;KF--L~z6KwUV|X%h%==prdW!B$Y8E*J(*b;Igfj0o z+7Lq=T#n&IG280zBmwLswsG{H4(wI>k4AHRoNmP`_l|$@V0h3M-qg4(0}!?&(`_a9-NTs@t7gd6Lj{QAz{nug05>roG=YNU2CW z+$yQ_FREQ0A&gbu0NTfF$KfGxi}ao+W;q1@HLF~5N0TLi)ev6}%O=X8N=mQ#c2G<+ zu^R@0KON5|L`CD>df2Pm!?kZ;+ z@|zaj?;hN7_Gd*FA(0WFH2!AO)fwhiW9B5eIz=iSSN%yR^q2-i>4#>?oGWG@9&}@U zrk3p3ul(`d6GSR5hiHApz%uoAD_qcZ4Zp%2B~}yEnEPM|qV=w?54yXFV;5O-dq7+1eTZ}Z_;R2ZGxA~Kvr4{)f@j!cYxgZ^GyKYH2I{nH zVe7kYn__iBY+Q6;Uq=>(y!Q`p7+}PPk&z!b7ihm9m<~(2lE)ZLWx<;5232z527>D^O6z`&L z1FU%?1}@mT%OXdsXI@Esv#~;f{Et#h4%{wx>P1hi`c4$>6B=y9kLzmPdfBnZ>F|P` zi_5_a7cSJPEOl$#AA%i;|Aj;lohkr69M6Nd#1`~Lvwz^62x26NkPGv{BN3+U%@|Rl z6_1FZgUk(Nx^AE%P6jjE276-l+HWMLI>&97lA0|hhaXX)%$XG2ujX_y;{?ZDTBfE} zMcyJ+=q;EcZ=w0BFONA2;7H8B$I?TUi;9YZm#0dLs;g~2K8THt1wrzR6Yv!^*N`o` z?U@aE3?K*qpk_am`#RQtNrd743LSDFyCDSsz$aiNZH+(FuVF$T!~`f&qOV^ZFnYjx zB=jvy|GnSAglldS?P>Z^&`IPE|IMK$*U-nmPVA&)cPOK1gMNMJ#)x^>W6O5s!PBOB z*hVJPfqrz_{pJyuyhLID8@~QSNXewHp_9`ZT9{_^qj#M1Q<}gc9_8z*r5*6^tH1i*5>lW_1v=E>$GwFuoe>9_8Xj$D*n=B)U-Z6 zOb|+eu3O?~5zvq}pY5`FI^H+`Wm~34vsHO|CiTxwfD^Zr41*~3JUNV8`*s$t{J1IfvoYK;5XcP_x&!%@6ptiBgO&==oJDpM};L^ z`}q1hqP0iD)$j!Nsf%>aq&!7S$%;~5o1*m_upQsgrsOnD?`NNMvN6PlB!r%`A(Gr|fb>tA ziD1W0^bvUfNN;u9sb3#__#>P6#ws+F3rSEBJFdsIxN~xzKZbi6A2vKolUg1+`g+ul zV=I_t+Ug#yN){3{Gd$R=cJ2rbyQYrGHojV!VtsX5Fl(%VcOJdhsHQ1d-74 z2nq&^&F4hhQm?nAa~(Z7Wq{VqfqN;eL*C5`$OUb>inRRsmN?tlhjagJ+&9;^q>*QG4{`Te|Gy8Hzcn>iIYxZ^r# zD;D_{c~;HJdYZod@ZwCS)#qZr(1Hs8ApR=c**^qiBI|0$OlJIv2+i|uPO_CKX z*7GK*{K=;+{5N3N7-29Af-`P_UFhUUe1{=V=Ga=C>$#y&R0Pmwo+2seHwaF_&u6dK zLjUWe(U-K9v!oTvBMQAzJ8AT~!SrV*Po$niCBXo#%LM@lJJ~Yii6s!4`D4J6YJM0K zZEL$Q7B-}n^2$R&sfVDVeqTu+Fcuk=G6%mLg7uY)+i^GlQtPL6#t+iWO8wPnE#DWw z)u-Mfe5tM5MX~~hWNnH16I?(Q1YbfcvruQx6c3{-me*%i0n z!DV7%)K}2f$WqjA6F!AuS&KTupVf*CeDj4U`nAf+30c@m+R>aWCyBNWxK~hGP!Qi^ z6Pov3M@rfHW7H<8dshp)4fylaLjmv^)-cYgr-Kp8Q(;~_pMnbjQmjyS)lI{m^zfqK zC4-&9w!27GJo|nfqK6tCnS&_!Ie`97*Y*X^X*39fX80N|X+NY-~ETB>{8qIwaiUUZ)V% z)%zr8UemuU9_a zt+68v4`g-bF2g*9vuL-;^%P>jl`{554~>|h7G>W7BQ%g;Kd zby%dkskC^a5G|*4=Ppcl z(98&HqGOx08`*9_u@{adU?$fNhSUC{&cE z_PLZUhc8c=ee;C`IEZir0xy*oCWi$cG!U%Mxpmc@yGJ4)z{?EU|D14{<0&-v{o^ZV z3T`;6@ida|R8C%ZE1SJ@vn2lbPRiuE=o{YNM}b)JvAx}75GPpW+qm9TFg?Ga&v&9T z=j8XAb-aaADkb_+_!4pGVtRxEZ%`0#y>!hRy35aE(k$aq@CzW|m&iS)+ep!%@znqQt|xD6j

~7LyFo$K38CA}^`R2RwG7*s_A* zLBAZ~VY$-}8k*9p<1_j-8bo9n8NFC^voktr<*lrIHijMk0mxwA z>}wl^GT0hBvxU%*LU!Io*;;((6*hNdZoDISrcNqacex`ye1V>(6RHl>)u?IUgd=Oe zu5pazqW=}Mm)0BW&YVjR=Fwvk}gDH{g*X{ohxM60Z&ot>gt?6H}bC)@ZQq8BI|x~N!GeLO;Xub83mun zOMfk9sQ#lF2yq8c>!WG!z^r?U*xWP?!GU%_pYyy((;bP}l#9?LS z(f4<^T3A{(EVHS$P59O(1>02$a|x}0<2%v zb?YT5nLC_NPbj)y*F2PwWE-JnyVRZ}vW(4$*?nMyozPki;>wfq)w{1lt$Fa*P^td#@G2WJ7af}4*H~p< znIM-yp$fI-Uy+FZLKxAjXSrj!l*x(oJ?$<=fEmF*wD&V;c$n(z?}kp$*ukLo@pK}<#YIMX4cOgPL-+9EzC7Bvx22?$*j zJ4c8MP^jD0n&uZrOP7|urFvFtdF7uza^#4ki%ZUT9p2xv1`=yxZtJP>7KaN>2ihP9 z=C`l-k*nSmYOS0au=3UBC5XaAO}K9z1USOiTK4m^>SOW(#=e4}m%)vBiK*nu9M1(A zlXW3KcAHnHtjv%Un#(B^H1*-hrCu*Ju(MA6fJFDrD}P6KAejvo-#)uA;M+RFq89;o zwquE9^TPgB#01{Vg{wnXCAjZ7u7brm@A{RV7P|mjr8m<)vQZEv6 zqk+{YU7>ee9KX8_Lk~V5Qo)$^DjJCE%F|i3kw|koVG(qoymK7Mgy@W7xTAy9elLZ9 zA4+T^{5HiaY339D}=4_8_Jg1i9cZQf3pQDHyYQA;XhAU`A|zM{?Yg) z;2C?uZ~Qf@O^d>EK6OqR$HC|RCt?NBS924>oJv^RMy@anl}iWe z1cS6R8TZyK44ZrGa8e&_U7+S&Hz>A9c*2;t4Nz*;Q;muemW zon5aK61kKC<^)-kjmj%B*FoN;l{Y)KiBSOQj4h7xNr);RBPcj3beR}<@9HNP#VM@G z%zk6g&F3+m3-rZepHSg1836ldI7IB@-6#|iB`@POF?N7T%n>hC%X-BzEsC`ncRNSa z_CI9H=Oo>~%0W?6SH6(sjKiPy>VS?e9TWM?NZljA$2BFZX?cG=N52d{iPT-ghoKN{ z%$wUb6O45&0=9WTSTZpquwF>qPS z?yn`j?9MgAoF!JM^pq(fv}gq+U7dWt*}MJUq(hWF;FgjR%kPCZkM#CJ^z*U|C@iQ{ zeLtgH7N+G%T@9dn!v<%OXsP)a;QVv=gl7Jb7GM9E&ebcK1%M4(<}FKm0af62J7|3B z8nR)d--Z>NYgP~ga=DwovaWL)hPk9k51ZhsQfC#wDBuV*=ho<2&~v(y3?oObxF=b0 zS8XcS#kY%;P%#?)IQS>vG=Oj<3SV=`JW1RJl&mnhY0LOhInR~j=UWz)yKGioKm>{G zLi^1ZkwyMM%=??`eokL2csS6@$nWXTO=xB^u!R-$p8CpNyMXszZM9{vrZkVWE&Klh zQs_A(xvk+55&3<~tS6yM{*&8YSy8i}t(a4ZhxwKqw6$UWRjMEuNM)@p^0g{_*V|R8klE+@O;BKNBTuq5M6x8HH>U`eYnv$o*^SLtbmA=D=dHQWu5l*I9%}2ea)UX<)y4>p_3Fk^+q0HWn#iB00!n;NW8QLc)nf$ z=mzKNRg6L){(M9pwUyehyzuYLZY=xwtKztOI$I`9Q1r#1p!GQyh?z%;M#d7(5E?vs zFUqTku}h+H4c$io6ll1Kv8#x-$~N1=>^3l|FtV?qJOtaPmAQ_`*EAG(zvT3iAe?4u>4Y zcl@5aYI}hTWf^HW`O@l$Z?diOp0=j{6TB69_V3~_>B~ZaRFp!UUdw;Klse1K0+ zq=OudL^#X0RVS&)xfOT-r*B1`7S`5HJ=F`vu(Ts;3Zxd0ijFj;02mw|eMFLJ)j$d~ zzjEqYQT*H1zt2NFw@{d6^7lzd9(7C79bB^b=oaIVqRd zMWLd-)wBxLs!oE|m&A|l_!*Q%4^kK$gL6RXHM~h)mZj zGFScjeUZ;?z<~F~qC_kPr7G+ZRpTjS&Yxc+)g%jb zfI*rDz-9UT3sO{P=Q%2ck5dq(>jM9#ln)PsWQ)xaRNdR7sMO;rAm`NkpY+Hhk&hZi zd{mVT5aSxmt_@3pY{=L5cMl&qGP24YQgLsEl^8YaB$@p~{D5o1p{ODo>7idACHs`h zNkLdOe>2O|vrzcF8NEn>3>AYIhVU^0MXpm2iNJsP?) zEmgM1%`dj-roZx#SGsVU66&uN9Q5q5H5fyUKBA6*xfhDoD4bn&3X7#se)jZB7_ygb zHEk~fSlZRh{QA()oO%Puj+-y}O}qhCc#q~oMFMEGZO)o>utY%*0NBdCvV5RiHIqQp zMW>!z$fXFXd-5fn6~H}NY9jN~-0YE%yt9LHreihzw-Z!J^Py&AZh(=|T*U4tSB}31 z0VUxs6SXegtc%=1O$Mre+VX4mP(7&JII)&!<&fgqhu-TlzFykHBvtRG4 zNQ5tB-*k81jE!*xRet$WQm`sV@6j4)OAq^cH*B@beD>WYm2D*%KK7`DUHwtbvM3-K z`J)x18AgR_ua1LDF8zd1!sTa`1@RuGmAFlTKs}YswKAw1Qe2hCWC1W|w|Q|Z8Z;J* zAvhHU77q|XnNIn-5cxr3(;uPbk`IB{A(YZrsz5gD`={23-Q7(DP-F&4?Y|JnF5WZY zR9HwCjP*~wCC8-ZE*PFtOs)I1p!$=3^^6&(uKfC_B57O3Lb-kk0BE_(l~DHHfTXge z_XA}YT+Jt~)uaO-0bq?N-c^in}}_-l+Dbp9U}rw@RK~S?x~rfhm^##)t>5<0K5y48+Yq zr2uvHKJ@_V!xUv%P!vdg>pjFJ_72tjc!4hFD7){v)ZTMi@$Zil3><#OAE`4i?wLI9 zeW0($+9#>yM3PZGM&+hczJRk=jWY12!_4S+&XPpS4>CpEIiHsj8?3?zWADm{in;b)> zGWF;NcZOzo%rU;6&wMKZw}MU}3iUN4aT=4&vpmKdJoAA6?L0bVe0)4?p@?*Zxgrv%HVzbxl}LNUP;cbKDV7U%+0i+e)KFZxGfOY(Nx&C&se; z@6oWH08U6$bD7VGArKrlqF_2wVv}fO(i+7ffxhj(gp7`7&jPu|(ZeI3bzq=m5R($S z3h_!ZYqK(hL7N|o{1*6CY)vbQEZs7*kdyw#${?4%%4HaG4}L7LuXleZ6gQrT9?m|~ zH1D}7QKV(oe0qEc#%-7^Yhv_Oy(uWT%zBcLkg0CUiurRlD&TNO$64zjD_i4~Sdovu zijd`Ng_@}>1s8XT(W)r=G+Nw$ka)NUfA=o4&dFQtPUrjg=M)t0Q+~3`?=YDEwp?`7 z_i*{r5(<5ZWN?T;o9GIxwhC98Z`SCj_THZx^&CK!$W;XJc>C~7INes_8tkT8296&` z-tNnP=gxKUm|vZc94bqv5#7eM=v#{&3QK?MChgY35Ya)PfC zBRRvS!IPa<$$iyrp?Y9aH0?xo>h(B`70>+O!HL^&>4xRwDUZyGRrc@h@s?=@Ehq6+ z0~4ONJ3+$c1;*)mVZH1v+J^gvprca8-T1Hsq zzN^%r%9yU&(X9TR2{{hej^=a`x+BSBARRiouYyC?C8TMF)Vo1x-mZ6Ty^2bbk1tUR zr+4p6WfXaM#vgjuhxMtZQ?8Tad^#_=dMI=uBIMIyTrAwuHD#b%ULQ&jc5`;h#Ppv% zU$%fs7R>XKKsgUmH41c zW41WchRp`G@IKFK*x|lP7Q2V0>_CIpvg)E7vh=uF?zmYt7k4Tzoi#0?d}#+L->P0- z;7-3YDm_*5+yP?Y;ddK^o7<(T{r$fNO$D^O zE+l2?rXKDAi?vD#4Aad~nbWj?jD_b=4GDo=Q2vwJ{`TtZNpzWfaC z&3%aD*-ZZ68s@MFb|!)X{nL zZb@s_Sbc+O8SDfB4K>#|^qz`-{B&j)OVC#~M)hVV-%Ba*(aIUr51GPJIwulub%z|* zZ|=e8=tjKn8l zOicS!zK6CYV<_?v;8(GlUPO5LUJ{^0X8>|Vv9dI*p3ieAZ4bZq$wS_BcxHchi=RAk zzv;nm!a|EIB)Cf3Dk;%M{#otwnqde%ZB?Z(euyG);PE}wL3lH4h+Dv$n~@R^*x>I_!Tvi&%h4PP ztqz`O`D6t*vM_b_L=_3pP98?)9XXh!-S)=W#-x_yv2@hqYhbJmS+|q@_5TP6I95!# z8n793+)EHyjB3etZH>a-^2<$MKsAi}cHf1-6q518{MRwisOB+3OC<&h%FCOYn~|E% ze>_L(em8$=7;%^f+Q1#XjAIFAE7B00CLtTt`KoM;x%=yUfP* zHqG3(JSKCM#={nd%n!Eaw#qfmGh;PCjng1+em;Q1=Q5Td2|9q}93x9lqyp6q=r3Vk z&*KH0dO{t2P#0}`VFFx@t4d4*RfDtK4BgZ;P3^K-S2fz*A7_D$t(8KF-T9-EaU>6d zqh+MX{PW=9fj;HVUe@?96jlXeDlGx6wv#vYK+QnH)a3Y_22`1(&#sx#%dW~EDuYIt zXWrGRE|G04o;J;lN(RD85Bo&W@4y+mf!fR&%1Jb<`({UAz@B@5ovQ?}e$GMw>z(rA(KEPwXCRt_oj2Xfw8@VM>eroMC9$e7$Jk zSYQ!hn0OtCX&Rmj=nN2GzO4%ONIic(+cmyFTw&4`gBb~%*T*WEE{8xgb8i$^0C#20 z<8iY%066wEy`IfuuH+pvu`kLtPY+%iZ_@dGswG_~6&Q3N?r8y?IOC&aF?sVt^@$RE z&LECFH)-1CP|?et@5z1+P+b0m8g18k!tsV?;k4V`hISzay%XbKpZc6yqn`iPv>TOJ zUS8fl8uy52X<`e~vYG__(Zn8HXI@#rn9|;-ap}Gt`%(#nt z!o75Py&0t~Iw51Nhn3|O(VuLwpaV@L-=ONDY-@sgK7uf$U@6Wccdwzey zK4E*o6&Mb=RpI{nL~@E1fH%`=rxU7dTog%^UdpJ~{DfT#L^$h?{}BL(E%sR~A*^`t zmiCMt=fkd5N=L7u&7vM>MDJ*_jnK(A>H#O8U>&TaHFU@WI?9+|5Zrom3d_}c1p+Vg z9M~g`xl@_N31-&%ph?XQWNS?`zPcBxqL%t|c3LsqChk?Vvq!MpgY8OF(`x$7d2iEU zj1~V#UI9PEYBW>G{-k{X_r-&iIOA+q5_qh*i1^AHqij2|TKB=pd*sEnVgNqZUp)xf z^4S_uEd4wsKyGOISKOLqm702W=vC)-cEHb+w$<&C`ZeFbX*jT(no? zMU%IqAi99Z!D@OJW94uvG}5Ep(7hRU1J`W|j&ZD0QD;YpBD#9#X@F|D1Lnd+h}};{ z;5?(9Kft?dFVFCG$dn;e{Ug^Fx40R0{|5 z{!yI9^fk!eW40Hxkye-wG0Bz3SqD4}gr_rRRjMu_&0nA1C~XmXGj3vj5;Uxlb}Pm^ z6)m$X2@K~)y8~BYHj&lym%vO+vng?Q+WcGiF++&*WH7{WSM83jRasTrNtkRC+Ycms zX#>im3_NpY4;tFrYfpgXuqvoJopCcI@K0nYXN(fSa-u^hx}I9JA_FYJ`p7W|A3qg= zjeIh2$uHl!9N(%V2%~#T{~JWaZlq8h1;VDZR_O&}ipL#Gj1TS_Tm!qGu2w&KWvwjS z_cfP*d(*>^!5S>Xf+zU03j_Rezq1y_Gp=Haa2b|9N2V8B0U&eai2POph-rlcnJNf2 zhe%HbMqYJDD$3eOH^Ixjz~Q&Z_(Bqp$4*waLZLG9tkX61;OQ^SoRFhqXqyWWtNX#J zxFe%0a=g!BoC|UCvJ=DX*Mk_#SPGTj8^(EB7YdJph{?loHAIjbtuP$-N11R~(x4ie z33lJRF|hkg==5oJR#dWscgf>Z_OA+y;@GfgLIyYhJBI-`nu``~b=?KHgU;q7p?>2g zB4#^^sB821;`Z~4J+Gh#auS&cWYqiZsr?xn=HbGqrtB%B(`Hh`w`JaG1{D89W9ra= zA(ot|0iE`An;D?GA;oE-)Zf?y1FR=Z=+<2AbY)~S4lx&{Y=WLX^rhx8mI89V#XZlZ z`4#sDQ(Qgd-AZ8bX3c5ffArq%720iN3wS5;T407Y5#z6&P|7Qw5C%Q4R4{R!;eRcO9E5c1quI*@uDpcn-Ty+J@EQoA@OBVk|Gc_$(F8KPX zsONxsnr14x(o}R3Pg0G8^h#*3-TzYA-$&W>@i92`fcNft78IWFGMt;#H? zDOG;p=;+Ejm6bC9QHGFwRje`rsh@iIC>O+;yFYGpn@?u`n=$~pi`fGv{@W4f@8)0E z%>BA?H(_kg9#(hu2PZD+cTfC8J%A;jY5YNp$5Y!WiIa8K|$QsREPyp!s2~N*0JLy_^ux>Tu~{-w^9;~%$Gvhi!;-|-fE`YHym0ptgJjep+jly zePQMkUXjAZOwY8Smy>8{-0Fj<+*q0+_Cb}Rd8y~zNvKyyfFfztHy%lk@Ab{S0scrR zu}2=WruTjXV!>0jL;a{6cU$AJYTeP}>IA9k__@V~T?vLJ<3+4F)DUZOn6V?Ae}Kzf zN`nompT@O6K-s$56GlCjOPmO9Dg1md%>%7p2T+z(DO=DgUHQEY3^JT%YO z;D&d)eeU(|@wd8cz6js?WR-StyB^CDC>UR=8ayL(b9zL164qPL`z7ta;C7EV>;%e@)=IunC!2Bnwpt;ykGklKntCrd?nla+VdGI_bd}#&&`}o9j zz}Kxyp{4@4y!PPZC zc3^b=F+T0jG_>AUc%JJ)V^ zDB{x&XhE+CU#gmLywZ2z^2Iaxg=gWLG5Gm_c6U*U-U2xBvpK4e+*3JqSFTmh0E{BC zttSTym=0SIX-Qd*DFiW}QNj0!h?o-|8?UJrhAJ(FNxQ21L&FOBoK^+iY~gLtagB5( zf`de1^cN6D4=`T4gCMijAhAILnk#%k7Ivv(WOM7ni+4W4^Yc;>Ldgq4<$&Z@%amo?8jS z+1czamhO6OptEiZHhtE%$I#=LZ;zP^) z>}G)S{q*g6=+}Qhl5XCAkQIw9g%2ra=r2i?5K>>&_kDSpbR%^QLat*poYIEtA`TFf z)8co6I6lFbd`$L-W)t~Ogy_SkiaCO$YQ#N2%CwdG{S5u+LWyeX;TAw092M!LQ7k82 zH)5p{>Z{>#xh$50YbdIJSr^{oo;`Al44~*FG>X980U{!8^@e_SQrxP6vQRV9l7#!I#+%7)5mt$J~uE`4rU$&yr%wUiMdkVs^CrWxuB5Z z1rVxDOVxjyzk+}1&W2wZfFY{^VexDGS@xukIaNqwwg*PwtJ){FXKn~_3T1QpLr}rE zTSHK9DO)>*pYJ-)>?=m$rf4CYpqpO1ZUG#i)SHgW%idzL?6bU7`E0dCgK&3S>6e2B zDXDcH_5f~7dT#OfAR;~r;=ZsbLS`>Qj$fs}3M7Z_>fDg?A@5AvJ669y_r~%O10Z!x z%`=s5$90w_N!r<)`??($@v+Z6;ox#`rrWaLs6~Tq%wg~i5RZYvu}Nqj{}HR$-6axJ-C5!u0ms_L z9Vj1n_)0olcYXP3N45ux+1oO|Lem}08>))u-n4DiKxq_ee|La)@f6)9(gbEG#5LT3 zcGTMul`}3w)WxrcC8ZEdgY!bQ7Ya({( zx(~DZy0h6KgWummpS@sT26Dw6_&42!k$qBV^n%0V3(B zhT`U~Knl$xo9BbWe%G%*i`!uZ6q-P6oG{XRW_Oq$1I_KyL`k0-&0L^1TekDlCpq07 zzorC;Yfgr}HRqgAUp{m`ydS7SMG13lb?{j~L?hZH)@}K~uA}My;eQ9-BgvY`eg2`# zoiAKV@z^5Pw&*ke%}!Awo*a3!3p#vkYn}9nGrV%w>UTf^3DmUt7^p* z#t__qJ~|d@M-)1zW{qVa?*L3Y;KP$v5CkLFAtzeD6ZepeTTZ5>9eA<#50XKmTivg( zt9|vTxM&avs=da@I_jjbpg1xZOU*CHcV;YNfWNp2W{sP#Yidn{rlW@(&W_2!6sKVP zLj>ZT6Mzyzg*MsY7=8DQY&7`NgMjSYmq^}14Sc`Ld)#kuio{g^oG22}1H`?Hm6^{L zw+)p*Q?Yl27!xyn#=BFrMDPkxV@@3u zh*hk-MDm zTLV>Mff~BNr2tnE`RAI6Xr}!y#hRt*>ERk&tyqx zjbgPxIKSvz5i+Kt+@i3lC=hK209Z%?h?YG=t4*QaOJA7waoYmp*p%b7l2nSMpsyt$!pphx@kuBMZ}VMvamAJkxuxBW za?$q#N#xq7>(9G=SxC-H*VP3{le>5KunQ|GPhDNqwT4)3wH+iQa{@(OSgdT{EDETa zuMjD;vk}w2t7i~C!ZIQZ#^eekb|`MO&dJADBREIvad2$&v{Sa;E&1m#$5Kpv)){t0 zm^b5Bg9~f)5!5pMieVTKxCs>j-~x%?v>RNghx7d3Fd*}5Mm6n8NPr0_k0H_PlK8^OXDD35G+EiMGPX^$J=$~(yS zoT+MpiR*L6W9bIc*YdDR)Y&-xHO?}XbU0lBEv+^Ne z5GVj4x6~9K>~0LnE1P6vrrgKcCOt>zQ;Bc5Gki(#=Mt#B(|mEtEtjEaz$Xu}wr54~ z%sI=csTMqvz#9NI2VM@-7N?Hp5M-M}ZNs(3_>}??iVj4k(a;wVY$J>j)3+6E%X%VA zMFTwY%6NMq|8$w^)#koB{a;xA|Q&zJ;zIn&cY9i=8MlGrYpc)a z4>g*%gq`Fy3P72@xG*vXMbnTY(L;|kZJ-Nw%V#A6tETFRca&!DSM-v-#l(PqF8yPJEdOmO8k^g7jPhpN`~h&IX(V4Jkt+q#Xb%@I7=Qe4fq!n$-g{mjp?F4I@fHdiR)s>hmXvx2pd_5Xnr*n@4FUldYFB3JEdA zqSR-{jv5PKwk}hYSQeui>Muh`QnjqeNli=FHejQKD3@hYNvF;AxnkXa2NCLtvB+Rg zx!44Ki7MQ$`rb9W)nR;yx69=s_Lw<&tU5qR2`4ZG-|lpp-UfR8``b{i;;$YU;8$dW;J6p z5gy|8_4Rc;AKd@Wof8;woHtS*x(rl@T+1JZ{j7}oy?^&uY6?~^ z-#Ifol2jNHj^f4PPVi=&D{*BjPpd)%wjZThiApDSfon2;N2+wLWLsX$wgl`(Tzy=(al4Xsn1!g|e zn`kWzo!82Xv7uv$R5|ty|Jj<}1*p?Qoo(rRnJe19~n#TtJ-ETB@?(+C7mGp~~wkxwQ&V$(WNm4{oqys@>+E=>tw0sWB-PzR{)laGZ9&{wQ zF#Q!Z;c!bpslk@^;bI^wA3KqJviMg-li6ZQ3_u_cz zlFILZ87-ahB!!nJgq4?5wJ0H=v>+$Gs@<@H1oIgc5pW-*oL?%&#tHLZ*|azS>< z%T+c)8`Oo0tAWE#kp&1tt_gH?54eA-BjM{tqvmF2gH>H(tc{DjZK%DMnuk;-cH>fd z7+DP`KTqZRmU{+j^e8C!4At`uv3xpPUcl@SR|CvFvH+=NvwtNlQ5qEdP#jWNi7Goa zGz>v7_~N&6q0&-zsp(;Wl9pg3bJm$co%KN_A5ds1Z6zJ{IaLw$yg^LmpP=^8bDQ-< z#Yh2Z<%aHeH8f#XB}`dKFezwXtyLs7*c+n>l3^>u@Z2{Ri{01?5pWO^yB2L?|16dJ zH9VsIi2jz@;J}%Qx%jG(kyd;{7ucG~TRuA`A#^8a1}EkeGe(a=Jc7_YpSNB^2_E@B(DZ(gBTF9t1wQG6ht& z4J3f%h}~aRO9^CV*LjRQZW(<+mm>wfx#l(#c#4q4HV7<8d^+=~WM+xa!479MSrrVU z2C2*v%W%A=4!+m3yZ(ef+%jyH!~a@WQj!uj!ImGZepnwd;yG5W=Ik@oJ_%RCc4eFt zzU*t8ZqyP{U6lsL74r{-O*a92#gL0dJ&Lt#p6-YnvE-7*thh2ajRA6Ip2Mv_sMm4d zwk4Ok$e!kn{3xJ;DuBqNYe(ql09%iGa8@E4^fnbS)CgYXih)Uq z{>FynV%>2IQBw5DIfx<8{~xBV0xGJmT~pF6(kUoNH%JRA3`jR3-Q5iXl8S_M2uOEH zGc?lO-Q7bD%^kw;ziYV^hjY&C{l@e5KJ)X}oI%IcREMw5pNO0$<9=TVoiI#_(tb?7!(MRU}l{t!9TfvT^ z`gr>!5_K|{`v`ne_>tc_)_W>{K+ul+RLE&t=4yQ#eqV!-vUFCyfB(J1wmbTB*I0H; zH9OSc_)2!I@8Is^pS+j%f(L%m8$@GE2KB3t&OM6qP_Kxks&=Lr`goXm|ECzih=m*4 z*Mq12gYQ0d0d1FgywBTKHJ^5(C^~65^nUz$YrrE54DGtVZzLLd<8kk1vs%1<8oj%J zo*dredKdT2pgZ7vQ9U z{9TLeKc1cx@1XkrTkXkdUcYZbz3*{J7kFs@g7mjQYkR1Eb% zC8z0MhiKF`bb|gZv_JEqjtSHL)I)Bg+F|W<)YK=VyCDnpeb28wLMeo`CV%{dSWPUD z`Hidm`J?_&&!0qkG6u#Bv60cy_i=CE+?)en(rle;*)APYb}6(+?D4oIQq+IVuK_cc z2Cw3wUZ}pyL+DNVR>3L44x=@O0ZNtXr->^a>pmkpkA{a#!hh{4zdi1&uM7`~U)F#p zcMg<426~o-qcSxQfSz*lFpMIC^7y+&R>I|ok?4>Rs6z@pgVORo*-(G=D~`#i9cr5N z!|pSC9yTct9aJs+cXiy6j1yL#+M$@Qsi8|D_0E0r&;w_t3V9+SH~y=CeY++aRGfZg zJQ!UH4GH|P*QS_W?LCDCxlPbKJ=EmL;L906(|h@;`Pq=RRDy}N%VEuAGMLG27yoTuOsfvfbvi}Y?>2=H-bI2R}qyHm$y--@=gGKf zPc0KVB8_~|+zu2W3pJpjBO3p0d^}{GAnUc=_H?3u-*2A#iclVg{QVUKPa(xDv?i?y zs=R}IF3cDs)l3#NCT$wedfB%?AMxU*p4bT5{mAoT4tfV6^CKqRKOg4bA)=F?L1Uix zAN(6qxc~WI2iN^zxMRvq&KOAc9aM4tlvYPwck281<=nd!?x2$6j{7cduCp6ALu1+( z3-=ySz*D%+>V|Iw?Rk3aaHiJzmxbwy*#S639v3$Mg3Ll&Z-wqcpsDeP#y^L*Z;z7a zjTw7sBA<6nuM5H5o4dfLbk>iW$F$G^7Bs640s#<}!Zo1%n?=Nlz6@VHv;C)5Ys4eY zRF3q@s+^%o{IM0|JK)*AK<)5V!@<=RWcEhO0$vBE7dy`XrRg`^ik~rWX(}dVRyt)! zJ7V@UzOOJ!%S4=I6wdt0GL^mShL(sezoe8`lJLBBvh1+a<8g{u`M^&g_3{;Snt}Xs zI6?pi3?jb`j?&*hb$Zzl{fIK03a@RyaMb)Gxhfu0EWp1P!%4o z1w;(1I9gkgF4toodVyT6DzBb?vBlK$?~>s;t4oZy_$k-@zSHs-^SW;vi9)9Xk@g!? zQuu_L<0XmOK{?2dUiu5}C$qDRn!Lb#SzGhIfh%%}`>(K)QVDj_498GHVe3x5`#;|(*zaLA_pu$Mn}o) z0!Kpg0_tBiED!oZGnJE;g|CDn8U@NX*77rPHx6zvMRPyxQDZeNw`A6oREw6E)E$$< zo|lfmyhj6RR^_@Z({xY}8fFgZc@+dxssPDRiPX$R)5|v2qI2cj0}oQqHX&@n!i|ud zt0PwA0v=sMNYC;#pDhsO^=m>hBExd|wPlfj3wMx3S?oZ@fg-^G468?Zr&6jIQ=(xJ zh^*4}YAD^|^6GpTc3kqFsG|)3D4bE{ox#$v4KL2ySRz(pR2Uz6>%muawD(iU?zz6- zm8=s%`1G(P1f=lIt>)9>^r8a0fP}G&4Wt4R1~XW5clnt!AW$7Rb1;0o{;wARCt^v_ z0FtK^Js?&JFaLZQ_wPglttyF$F`)*(aD-K0e4jojwz{ zYm>O}pfOByGwrR&ric+)(C@j0F>mLud zm~?6*{EuLTFiBIqOPTXu%muCTrKYuxn!U@9_nNcF(x-i zXL;r0)G#@A`tbd8DF2D2^)mwICJSe(`21I?kt)>N(F*Z$yEEF3dGIC`8h?9&O`m1g zzjrl>sBD^a2X2w^^kg#omn}m``0aJFw9_ z{=E_(5&a=~;enNsP>PDmwhxV2gn`uvrLxf179o0vIeV;Myi=g#2WfSPB>JbJ`%a3q zI(FMlJz;;zLjMXDP(CXueP`+!q7ZRn5sYn&+(o9PBpfT{t0jnMf?F-!s`c>2WKCqZ zrrwY0lcDvU&nKE!miwggRD%m4PyRiro92gYOaeYvI9E3U>d5=cw)XX({Zn`=0=_NY zpuF@ zsobw{3dVFi)1BQ%&9)}PL=nGRm+Hvpqoj*3{r&dY6Ze5im?8i84gjHMdWq&XI+H|6 zRvDk>cpzRLZ>7|a#s>O$KqfYh<>+>;p$|cwDq_J(1t3?Maxp$Wq3It$I8-GHz(PKe zTUcg>$&pji)L+rD(a39j$eTF2aBxVU@@a>i!F5U(P6@sFe(Wa`yJJ!K0L-{Bb9d9> zPgJT(9`wMAwwTZcWzogKd^Gz+C-6aMN_ z*d6o1i8Z4gX*ElcL+*mXSNF>rmNxiDn%WtE89q!(`qSrlc*TmDz z`^vv6@m}jk^}OI6A86Ns9Zx;5G)zNQ8L)=gF`c_>bps``X%=L@dt}Lc+W(VLdjcIR zCvB<97I{Hs`gf&aas%N}k|McPS9={)s$p^NciQS(x|qV2Zv!)&;ZBp;Wrs#4oTq0&ajQo5@Z9B%88pGE_63#mTgmbR za&PVH{!ga3-#&|s9ISQuy_U+3yauZVvgt&cQKHXIAK&l0u@>9#8GspTN6a6v2Cr8E zKJOM`*_hNtKQAfxuA1db-?KDlDHHCPyzec{g433P-mdkpzQ~e0xr) zDxP7-@U+$?=3({Lj+KuB3y3IBm)oYLKmENnV-*n;ZeTU<70B4d31IJ=w~p!&YZxq> z5x1pGi2M4S*1a$>ObS)NpblKMCN8DyIO|EStG}};Y67YkTnhO8N*Xb{~ zndzU`7=Og1{@U^CYv(H{KDe{E!i!*}+GnqR-1t86e}E5~8byiwH4XWbGb*dJE!(KR zAnt8ij!uhIizX2*>8H0aC;u*Q>eJ&!YWMzI*1l6}WT+N{@sf!ta4fyDMU^B`pEkV- z@Ebin-R6i!sXLJ+cBB}jkpHf5`etgrCGFdrGfXVy!J=Nn)sVdG|#~ z%VyIBy8)uF_Df>=N+Sj!24R|TZ8WJkW2Q#if>UDmq{&F^`=4@yY+#LyAr&=>Eudvz=r%4cVRIGUkZIBeDLz|=HB;I!j$?VY={vCyM>W;?N50>-bb5Q= zLU8mYD}`a_M{Kup@p}Xe;O)oZbB!S19YP(%^x-|(e)GWb+Kd1A;arycob~OqV!_7a zYpi)BTe!yKJxi8A1>w|DEWmq-G+%$)k5cZcKPB1yXlidg*QH95&xYJR$+S{fGK+;- zo7!ON8m2w3>O9E#Turz^?g2A>?TEX>-@vRNl0>qen?Sr69ti2y|8JisDo%A+?F`^u z#$S!}u8Ldm5u8yYA$HtkpP9$cpw-p@-iG~~FzHWCo>(>w#lQ_T(ZtkSN6C>5b)mc0 z6_;P;@rx9E8ge$MavStJHa|(1j?P#8+%6uN8ZZ zcB3EB^7hKd=2dj^YNg21XkP9P)gD~?qnQRb<%h&9l2OZ9mR+AdivgLI5f~2-F+`)D zoTeSlIr++e(F!;Vi zG16}g>x^3Y`xTBVVDt3rl&9LS-twc`CiZ?=%X*1e4=PA9ouBo0m>MN2}^7;0`R>ZD$(6=%NqNr~|( zdOx{IX@G`Ev=aG3)Y^(7qP${R5DK?SvS*KLGeQ-y%g3U6+|gD$*!-eX5}e|XkTH*V`%J~ZkWTa1C3HD>Df zoYtynR4O@~udT*slULvAUZZ5vq~f=%)%fr+$OkT)`6&FV7l{2Ep0PuJ;dM#uYG#hX zE&5kZ`@Mq6pUDEPT4O;3TpiYLxzE+UrS(7vEfmnD5mk>yBd^bD`s^(~tJ29aT9uG8 z4Ws%fL<}P4C29xu72B6sTCoBs0czh~+KDg&Oqw&@Eedz^gKpQTM`LxV-=lZ1;h+$t zqp#6Wg_qzAFR0hM6-E425~HMI#dXf{Z)&3}yQ#H{|7jPm5yhGajP&5F--$2wN@ldw zfSm@MP1p2om|}vi3a1B}o;BmUKcFpOcy9S8t%& znzv@~zN3gpx`xk)PaUibU{nZlE%9>J7-lwzG1SzJJRRafa#C2!5G&}>6!mEwbiCN= zjZ2a98Nz9{Zb+b47`WP_IQODP7DyCtRpiA=oGt{Q|CQx_iwriCZb3^GecB)W;zG z9RqP-4u#OM>3O$3xEU)`xxwqe*)-$_w(!aR$$_I0vCxs=)*fXv4h`HUEZNv7oB?EJZkkeEOfuZWTl!qw z1V$ce$4j06Y7~%(K3E`Hh43D9-DPEM=EPiaBRz zF(Zc(dDe@UD)7(BPmE6?B8{{bSZH;u z)vPzc0O&+P(U_83DHR&T*IjGF-Z&!sNU6`{Ni>*(UgkjQEtyD_p>gS18r5G|sF0nK zqfV=#>1`H$`E$wPpzYaq+so0Nt*ZvEi8?*z=grG6!{u0Fh9TSAHF`J!fmGj+0p&!) zk^}F!K^FphdmGaUQta3jzej%0^=l{h7>sNbX&(x-i3Gt1PsN=LySgm7x*WRVH>~Up zE~I$fEb{B>!fM?T|4P(dYIbgJ=c_xvhE9H=6~J4Q&kxi*U_TP}+P1eK^DirWsorP?M)6qTH1x#gl;nE@R|au} zsX<4_{~fWj7Z3CO6BlxRY>Cw>6a%#Hh;Zo()oX;U2`L_4Iw93Qaq564jwZqA~@7eP7SgLq!tKeoT zXE;UliJncnhtN2-M|fV(9q1Ss_?4F4+@L=?gp>dKp4!~!;KApEy{)s#FEY|(_?+xY z5ed2niEEsSG{4&U(ER0bsw`|84==X%R1z{#Er$(D-Z#U(BxYb;UD$K!jORoJWJnh>y*f9+OIQeK(!a~sHymjha^fW5yTRhF1hAV7i~~x z8l5#GUoT^;@2e2u(D?e>FunZ6{>;%>P;P0Mppy+%)p7su#9Y)cjfw?mRF*Vy zyO$KxE6AryDlPCfZ9Oupem1KS?#ZvtHHU_pF55N-M0$&eGdp`(a(*(Hc^ElkwVxFk zMXC=A(-9&_3cimE^qoQlp<*hi?cO$+aqbRJZwbwKYQ#zo5%+nA|PM3H3oC!$7zLRqCJFdd&F&TCXnzsoc&%ZNP?{>bk z%LAf9J-f@P|M)&4N%mj-K(`Kv+=GHOk^wAK#d z490xgclB5r9HgyC0^@vEc`9OluabaZdwUz*O-hCbCh~Fqm)hG`f^u^cp^nep(!HJu zjbKD>lpGo~!l1AL(ot1a!)vGCF-X3`86`F~+5C;#_F2(?n=c{7$qskELQk# z(gcV7L+Ad`W$~Eg!hy=KfQF;^qAG?#-9K|i%igf1KQmfEpE35gPR>1lKJ1w9e;S#` zA=`8~!dfQ9YepfOYWIfnLk)T+`(L6U4jQW0C_HNKworX-dv!eaZV)5lnpeSRHM%wE zN_OD~LmfF|Dtwq`jh4rGOln19Wmhr5H3;0~9{dCgkogn;bp0!{sw!;uI-6as{yBSX z$i`!=8UDYFi4xOd&%nXFmbC|5`|H|TWxAMesL_3>AKsc2W$%H#Q+bUFMyOIqe~Zsx zs(gQ;5`m0QP+5_bA1K0fQoW{CHy}48^GChYu-LVR<=fT*)p22j=bfMH+_Pso{@JT2KoSqY47U11w} z2tB76b|%wqOnMMaq)%(!OJ#GB)9Eu$X*d)lWQiAOyYA}w73LC~5oT!Hr}Z<)MrGkW zLz@mJ&LfgVDpJ0>1k@%)B2@6ZxOTOof(YC4h@wblTt{Q{hjO8Al`sX`px-aV@Uok8 z3ai{RVQtBd_zxy9eMrNpQ=ehuMtt(c=1MISXJ}079cVsrC7iuecvvrH@QbJHZU+C@ zuK!%C{AYXu9n-_wSWTi($smAAtd8SaiHvJV_N%-X_!l73-3<$Ar_6`O+wNc(A>NPDF-(j zEUnD`4(WqVk;U*YDk4A8Zo*|1g|ME$=nPqcOsTZmc`bwC1?t?Fl=mei2*DFrmUH+T zNe(C7q8RHCicq*5BsD7W*ZpkRhFwO^C=y&e3=&*ex1@kg5tB&E4+e=y=MopQq~(@n z4>_V*$N#eUbKkOLGL(JS*R9S~h8E@7NovYZKkH+Nz93eG9;`Y+HS^)Bx}HX!uc&g& zsmN~SGpU4m?6hnlF9yLHNBvaQbbvn>;S{KCp8J%~-z-{hSe80AJE;e@t74);UjlcM z2{dlCcf0#p^ixEkeU0qGEh7{%;xFI}ABBbWf1$_7rzG!>7CnTd&r zqpqNDb7S(P>d#nl`>sw%p9R!1&Hk?754S2MXPKd!lZ5wus~QJt{UGu;+pN*uTh%BD z25K_jE#7;EGl_Cnx#!ozTMvKz2p{x~k1c-ZMH(L;;&b<^*~g5Z5yyYF$FyGn_JAM0 zueIjOy+z9j#Vm6U)TQe3_rzo)<5tS{56u*$#^!_5;*mkVTsZzV7wOzI?Du5gGi_Xy-@A;NjqjMrH@f zTCFaMAU$L@(`q9J?Cz@^5r+b-(7kNhdFDOn7>NC3ivX{#F(Ur-d=QKDp zM3|@P^B$N-s^!<_T!dyyZ$*7Ggt0t5uRseEjqP9#ZKFDTig}_32Mi4kb z;5?qNF0L}vg~cauP9p!VAFxa)ndxBh2CvxiXH{e-AL9Xz!L(VGD&4+t!HJ6f2g98D zVoU5i43o-Kv1y}&j}@OyMRrkZ5T@ht(P}V5s)Qw=61{s>$+B@I;C!S7wd?HzboUZG zEM#c?U%G9tbrhx32!tl?n99y7Sp@W}_!yb-#lK=l^;a#81EpD0HzFgfzPqM2ohbj; z5V37E7iuV2?WHS>htNg4O{^z{NuzSJHtNCr5nH2Nfdu>fEMX~Sw+3f)_7M(37 zI1#5kmV3*{%e`yCB#xV!ILY6)2RlUyrFkeg){zhitqe>ZhXux%Y4tkNAW#R-%2_^` zhHn){tq`$dj$ZOvP8D(u0v}4bIZa@VbJ?>##Bv@6C7ejkSO75tQtjN|bKdw0KtI{~ zBUiS+{%=`qj&SpLyrTiNAffG&c#A137lh?F6EI!8PdY0*>XgcKD2sz@%pf3NoQa3B z5z_HPn!T5~7}sw0SDs{G?p(m&9*O-i-t*20GbMYrkXzFCDCH0nXBW8&<%sQ6*lq?fD!Qmvz|k6G6xtYFrtEHv3SQ80p`4-9Jg!uq-XI)R3A~$n> zS7LHc^w*(t+mRCP{Kp7&2j~tnZI-&QG5F5EB=f~X;N*~*Q2S2zEO$}cI1wr$sXq{s z`c=E!+yqZKz@%!>Dp`9b)`c5TZprK3IFV@V&26~Ly=7RH!dpfc=QdMX7U5Q;OceaJ z(eslvs!!o9AL2?!&MNg~Ko5q_*4tqEwe4v(!)CBrM@nA9$&0dbe>hzG(CLlqyPR5#UIy9AOk2 zo%CIOlfeox#R;X;kNZ6a9c(5#4Gtq?wsE!bpQ|#62Ddmw@R_xCpWe@poT3qE2I-`D zSE*k>OIMW|Ofef9(6HV6v{^pQM_1I-w?yI9u7bd>+v@<@PST|EzT^iZoyGnHd~WL@ z2RA~*)YKk(DYyF7Hss#9jbMVMKp{l?<5(?_sZ4Uf-62pWfB9PYj_10s5s{$(_@qzJ z-+}eX5d%59*B_$HAL`$|?GjH}B=MA%=~(DlqyYL(+%7`Yw6v(U5!n6VexOI7Q=}%N z3{Gmr(Er7unx}%b&p?jHWE@MaloFxuva+s^HAt<6tsoQS&s5;UOpEhR6(Xc>*_F}C#IG6!6WmjCI`1X&VA5BPTMZ(skN4>CO znsrH-5l5BCR^(X&28;&s&UZYp-`|1PY3pt?&4ZIZ*2MgplPm1oOynKGMq( z1?ss%%)~0p__|-wt^KZuX=qRiE4?*k2j#(@j={MD`H#E&08z-JVZ_F@>V)*V=x1 z&)5TxOS@KAWLachYI7-HfQr9vxfLhFY_ z;SCW+$d9EqM$>;TpuX=5yaGUTJ9S4(2LTWuZQTj(uf)J{{-wWNzQR=x*7^!>&+{A2 z+-)cs|NZHjE}N-=gcKCCky9%?YWL>#boAte6WZczO1S;HawxHXH4Zf2h$M9UhLF$? zBJ45J&v{&V<$AVS-}`YQ*?jxCaMz?ba4{?CgLBDKXn!!Lbs!mxR#IZKHIt)8#bFaA z*DGf7&ivW<`mpy%G^&5kyIc}^I?;xR%E=vnHZ;2Gh;vYCVUX+7k;v--&t5`2Y5|p{Xr_&FE}`MVMUVS(NT|jO67qZal`!joCSo!(QLHEDf!jDf#(6exi-$H8etqHq@ z`Q`enBQTKA<#a~is!Lmz;gjV>Cxrc`)0vIXaFOLkIm>JLIp=Njg8n|__W3WqKK;A7 z1taj4Q1>i}byM*T`^epbH3tt*$0(BU-&Wv_HS2jYq z>4_vEetCj5Xi=dq-k9zM(KDBI<3 z8nq8?V@Yiq(agz}==N-3X-nZ-d~9R?uJ&dAFX(&sN^d!UDVb(3`UNn@hy|cbizj!( z`Xp;T14-~6D_xQ6%y$0;jO^-2SzNk1vL13<<&RHFHd;@)r8c^2J+K0Gq=yMfR%opG z6KL`NYNVSZ%93dUkKT^IPjayEOx&T4G#4xD*BO2-1IM5{agIKk7cQvdnCnKi{o#9G z5Np*(juWtcrvf)wAXB2RjWOQhz{K_{za_CJ(RQ>@4wgtgs=rqd|KK#0!&qqQl#c~s z(C-mIzC^US+#AuTtgO5}r)hd?Tc7bk91Z`M2B>~^iP)LK!tud9;B^59K8I73-igK- z6`bqm6cYIoL=g{u(`g*k#dXf8Z;}7}1Rdkh*H}Eex32jdo)Acj?6s?!M(wDc^|ly= zQGtTqOosq1!9f2aC(La>%mXoH?@!@*&1Eh9$ZF7-JD`m1;ab7`YNY z#*=*!3=VY`%?b_^&=N+w10TSGPh@WlUBF*#2G(G@p(7}LyHLyb={C9%6}Yeesi=5J zLwjQicoA&+A|*0A?sf(kIId4Y0~to^{Upl)BDzjU_+@az-xxeK0Ng+FqLpPk*1mSU z4QmVjbi2&b6i>^0Jjkzp=ew}+!5a(6bG?Xl*voRqU?hC24^9mOZ;D~D-R?VUV~QmS zwDooXzmG3cMhy2%2xiM3!J(hloahsUV(t?8x*6~qniO+LCkVSk#sK6ZM zH~m~O7bR)R&ozBD%T-caC!*Hh^z*PtWi=8Z!cTBp*wH#aLCFFBU3N1ZI-U--P=TUj zwi+~>mM@i9@j9ehdRRM)1yN58bR@L*Wq;&*YPg6{#(}&blJxJ=j(`f~&S*N;_W_t( zlx3y;KRrVGCkgEf>wzjC8_r)s-jgsoO#j;1e)E`e6L^J9JTrhh5o|i zqLVG*Phtw$-1#D3cn2J!4EePEdS4XQ$t1}z3~GLPwmn)8-qZ)j%N~w83m^}jRelNM z+D7+Ud6g{4(?@y*zBFeQu-h{y=x^OAX1mC45XPXj^iSvB$TphS5!BW}aXFbpC=Lw; zzcf89P%&~h|HEP2U((?4li+TTHr{o=2iye|+kY+$$OpoBcR2+g%8-x);r89Vr#{6P z%OroDSnw|N9t{+N!xC;uPpAGB!VlGBf+m~Mxr2wKD7f4BtkLN{r1;h@^Rr9&w>mWu zQJR+na*NwU6;Uuhjjb{8?n|3I-x<}{J*FjS=#A$S?K!t0xAwAA{L8b9KPXY@hyar; zs$z}3_7-)1Xd#m7TTN}HY7V*>kb)#Xn5GcM^CsK?S^{xTtXDyTliL<~_4OmB8POjA zrQf(CwJl&XoJHKA$6v~L3v@^Jmtx0wpM+)af)s7x91)Ge1)2QzIe0YEUF$KW98%3; z_Fif@>juh)`_piLgoQ!hZ3UFOFEnkJPV{S$*zsMNY5ZKDWP{0SxRECBM`#ZX%{->K z&~jP0icd~9+7AZ)9j!4X_u92>_W}pT@$q%5{kmOl)dya)A9TNu)mXIM=9Enm=mXZV zcFfK;=#l0|X0t5pRFv7=O2ZhXF%C4i-YPie^h~7axg8~6$KYab;T%Kj z9CQaSaFux@oV_pboOZG0W!=fLk2TJVZa>kt7;rMuBCkZMWv(;jX3<|~LhGRR@`&G` z(cwF5JG+XvxCNAu4~NSYf>bH!@{Y+K5IDl{to!WRzrUT zeTQ7Y61V>m43&03<_F2bILTCN2+6vSCT4^tF=CHlXPf%b8Y=p(f`)}Y+4zK7*I&jE z%$80%7;A3xU;LgCy`Y7WxmJ&@wQ{pDBw?s|d_Xp`aA=Znjt!GIbXxD#eJ9h_>*+k~ z)9w6;{(2|;fKbg#C$}<;IsLn_h2_t8%LJ~*`OVjjx37dwqsyNyC^jDT2%NPFw_x2= z31cjr^C@bdu-O>PUBL-e$tT!C(7IpC1ucPk>AL-Ze zI&LQ%%P8}hTxSCZW)d97g>R6c1u|9GxF0h=8jmnu57hVPL*_bmuP6XwG8DJuMtNM5 zb)f@Z#9rs(@z(iV(i2mzylDm($AT)7ZFlaAWwK z{96fh0X~eWlSpF%jQiMG`Gqa*>|J04QnHs&*U|J_Z!ag+f~@%o`Sikd`)SI~y?+at z7e7ogcG*8p5d_aX7M`^3qaNy66JE1msz*k;?lFelA-Cl*UYE86(I7$1uX9|uOi7#fzZX< z^`as*NB``FI+&E}kUf^<=>pO*)8>ogUXQ(3#36_lDnIVcjiB~o6>#Zpxi?U_7jk!e z7c%9Z6?c8cPAcVgf0=;#9RgqcbyKnN%!ZH3$pt5D3ZcKv8W& zsFJAU(#pup@qAl#*uL(TIFh4S@#b8X-ThLins*>w_?o)T-Swxj*S>MrDHa&q{n8kC z#pBxCEpJWsSUg2bc?)J@_f0oI{Ftg4V1aIqW~viFu53z7NOKZ~od+rh=Z{HT)y{cb z&`{B!oLXQ?8vcoAET5UMeC7N(ckH)@|1KuQ&iHnTylkV^oOj4AXF+8-0^VXLWr@>X ztqS@c;(N9z9x1Xg? zc+(ee#2%{X8RXCoxvffPwf{W7#FZ}Elv&s1in6*xjyp;WsxPN}#YuAuuZxomFDuHx zB#knv(x+O&iJ=UF$9OO!AV$|qirbqW?YrsXmf{=wUjl7qed}Dxzo4&CiHnb)I-6e2 z_DVTCw1xh^8Zyg?byt{Tbe4VRe!iO>e=&6zJyqz92ktGtBmULc)FE^!ukyP6{KhzW zDSp5cQOkv@{w`8`bN!7Yk14FS*R9Upsc2yDAnQ<*JWPaLXhuEe@rJGkLJTgn>f;sr z{Zj?8118w|P?YG%P$$-VR5!0`$%E|A>3)&*Xjd`ga{{!{GLd@3itYIwJEBfU+dCDs z2o+~zAI@+GJ#VqAIPP!5u%;xrqka~#;#-o8ZN#1btFRwO8a?tYUw?8+oyUziI0>r-0)*27V$8dEHp)J9zYQnf zt3x4~(|_tPo{&7x6zUM@a#K;nQqRuG#m|o>d$)N?;IYr)ab%zJ_I%1g)pfO#*Op_w z#c)t2j?uNeyHc^@QiFf!u^Uk#k~P;&K{W#gyXY#}ug_d^yEzmkEj}vn9ZV zIwl6007;ip>`yIf&kI5dZx6&Yqf3a^rtgvR!0fgN=vgW}36q+2CKF^_qofjZ#S>&T z6{Od4iJPkawc%U2B#}s=jFD#&xYBvhZGyU-rC%)b&yMFl5bCK*$Q*Y>M)p3n6`p!S zJ=m&3E&qQW5Y60v!!-*KhZphWz}+&7?5C-?96bl`tSoMYdQGhzNybuEJJrn$=nh%e zDXFB?ffoWw95t6KB%kLuw4K-J9=9BG^;i!k%JEH;BRzxEFw^jk&1iJPMV~eCqgOr`10A&L--KL0 zoA&_A+OSP$j!iL#VuXb64A_=VzSQ>du=oF128a|%m7@gUCiJaW7WmOEZP&pHsh6>melDi7_}ULDvTB?N%?t2B3QpJSzHItC&NH4%<8Pqpx16M6Ozz zRWDE@ z^oVhxl^ijjs9gk^jzt!*$!Vj0yvrAlXj_?x^&5G-BCi~_8@qX(FG%z^hWmi+9w|&F?xBrnCv&rkiPzefNt5O)3uR{kh$)=??x-cQn$$Fl*?HI(YqwK*YQQsIu zU`(pb-xeee3=+X0!VihYuu}X4th3YuhL;AznK;mYrBo} zgev9KAM+-u=7Td?TFl^5k77Fo@7m^=ANv!V9>8vP*Jc#|$GpjUGvjMVN`ax_g<~izUVE1VsDrVAE%$RD%NKk0phEWzvGAVe-~nxpDi}?V z%{`iqE5N)**IWD7WmWCUxEUa^=o?SSSt;wVkYx)J|~9^y!pQ@$u{fc+3TDs!)hTRLPK$tKEy%{=Q@k0~YuZ5|LR z8pv3|#Aas1jp6>S8Ibu(ZIYZbeTc^IWh#65F~)de$uE(*Fo>}yjtWalHz}YJ<9SEr zz`y_whDzskbRz=AHTd>%q$@*A2bzYoTv7@A9|muwHBhzqVnzIjg`QF*vbRkv?@qU& zV*n$$wqHa+{@Q@S#*33Ia-1AH7%%y^1R=qXgKk-w+sovFK@qv&iV249-TBCTwh%{hHhG|vNpZnwMdYr zaRxBAMl1uO-cO~4@;y7!j9|Pnppb1g-0^tVV0WRJ%@|x+ESZ;|4=R(Pam*;tQN(-0 z6#EvVYYLjSBzo%%pLA>w6qxfJ#o4ri;aE@|D>llynvfNSF=B=BO1br*ZKBAjkX*B5 zuDmYqUq$rH^X^c2-+^zQoNi>b2nLnhO@_6uD)pG7QTbtuB18WQdhDiJXdaFp z1%UGOG4HpR8!T+ME$-kG5M|leC44=mixEOHIX6%y`dt+`y;VZEdtZ#{gRGK!6#a}` zZJQH~N&Y*@&#vXs=GJ0fv~pXLfiF~4HGm}(u#xX1)|QUg3yd|~;!v^D>>P~B=WWLeq1|_OsQ3}#yI}i* zLQzJ4JIK3Q<{#z-LdjwD_3F)G6dDLdxF;NsE3Y0Z8qv3W@R;J7hXQg zn3#zFR#bYFiq#S*?BUHL_p}HurGSitC+tiQtur zgM%(VX*3`)J^mfmZ{62cEu7>mE&?-^||{*;RCzzteTO?TdQOVFRhHNhdZli-Au-ZSn5#OLyWHH%&yD99<$3^rr`PF%6L3 zhHSD`jaT=)QqbV>guod6)gr0WSQ$(xRG}!D)%l?-C{%nwNV|iSU)N)PQu95d`;}h& zOU8mfYiGY{Uxxo^9?yEqMjoiHL#d;Y5%KK|Ql`j`YKW$XGN~qh^--QWy`--EU^J5- zE$YwP-GPR0%e|x?TbZqbRsZBdK9CbC7j8xt7Q62Q((^I^|A~gJ0)}|*!JSZfHjFvi z9uw=PKP*dup$2(Al1K(c%3QFuEtvumGK93WK;bVViF#)3pWCcILAmL7rO@QK(GZbA z8Bp)4-Gnr{RIXXDP$uN#UIhaV?Qc{+#IG=$OEz=(Z&;-jn60s|25!;oR^|fTt^TP} zT4?&6%opTC5#HQBdH4S(t@33aR2~C2bPW(sgwt^zMdspk?W^&kk_eSoau^9=b(nGJ zaKz*0KbE9k^_9kU1QQF2aUM|C*4m!)d~}ed_t(&Z2ccauz-FqUbB|MD`!xtspYrjV zLBr#h>w`K|i)YH^^~luejssP5wZ5Pn+w1z2=7_Hj_cIQvu#q%U$FiLAz^v?L4y{k>rEtEhn5zSz$})DizobWTTF^}h;-WU?*`}7 z_m$#;HW5Th^P)93GgVwBKkfQ^R|cYO$g@6l8^VW?k)fm^iD3t)TE04o4C6!xs5@Id zXC|mVU&7)ztgNEAzVQFIFk%|YSALs$kwPlP9_CWRYIFoC$5 z>kWTN?eMMMj%nPtsu!Vp9&l?E@0hG4dABpvKKu6}_ysoYa8L#E7Wo~n=}Z^_a{FD~HL@HYqs6nr zvy?Int16PPnYpnIm++i5I{Fy6FlWeKL+362o8Q>7ia~}=Yd%iGm^HYJ*-g5>w!)z{ zFdI4)fAy+24sZ`^!5CqjTKZ@BPRf68ex^kJkB6Z@?|I0u4|zoCO&=+d)f}EDFdTX- z$JBTZ-NGk>e)oRdMMsph*@0bl%vuQk8tyxi*Gou^n1IP}m7LnEVejZ#s> zHBb(IWzmd-rXt#x|8qFttJbrgatXs@)A3fBi08h26FGhvbriSiy94$4^&15L(8SE8 z1WsW9t`YUUPYT>wBeo3k5GnO)7`e`k{pF`{Bz4I;IZPn*!jZNvo zXOVjc@BZ;~vKb0~o8Rs*&tVtmBAV*KOj5H`3G|dbPME1aQ zK{*#)3nHJ3dBnv{?un^vu)vv2!BB2%*cgA#63*yo>mo`O#YKD(f;BUXvzuz*@;EWD z=DkMjH)mbXKtxc09>F-G1OwVMdU);{U3K9cMXTD6YYdEZs*#r!6|M(G)qms?6LX@O zkZY(2eOwY3ye-$7lKcko(cN?`VYtVKnyH{_^Sc3wk%dc3-!jCpa0m$To!rCxo^swe zGvoUo{@LDfOYB($U-C3v{j`a~{&M#F5e9?EtNl;_o~WkLj|QnD3N3(QrR#2K;doN~ z_OMy?t#OOICv`TV+ssIH;IF;F^kJe-gK3~$SO=+>@b*b-&JPSDf|<|h)8t(1fkVDw zmpcIk3I*!ixOx1-#L{m*Y*%yX6c*wF2ncscrXB5_>?19-(%T32DJqakh{P8MZTZqB+ zbFEu-5T!^S(z^>@HEl||ZFP4oJJTc^u`AqP;@=T&@LD^Y2wPjD+fjvIUWqr%1Yl$& ztW42)Qw8EIBZf4xJcBbLV0nFOnpl^X6l#5Nmy0PJ{O@y(WwR{(3I8(}0*fbc0V{Lu zg)7716G`o4Bwmu;vdzDTiIc4S$3=6Xa0@HW_hLD;mXMBP_B)?|>y$F|l}p~=*%#>O ziTmFTJ@za5@jv@OZUK0Zg&nFTo8S$<1Nz9&&__&7seYr|UT=%2WduEO`eg{Qr6Z6t09o6ov4Rp~V;3 zczNM_$Hrial};kuNd`fS)~Fv8cgS{NQ%JmAwEwxPCs<5!AoMc4><_*bCLf$>}9cMd=Xprr|R%%3~fb-U=L5zJS0WXS6fl2s0;pX+t&!%0?+?7f}8* zOy;s6g(xQ>!3a{zkt2y`!{^P3q9!`M%phh90Rt>epCLu4=M!HDk#}fi`U}PSfH_m& zzkKltu(otyfCCTV@aSmWE9<|wm2~k3yeJ2JE5=Sb1u^JSUnK4FkU2RYPHRN90-g! zG57>o^zEZ8;jT;@J6)IO`R?h*G6Em>a~5NIVAH+g)iGertauEZpa)tP3lVx$U(7lq z1~Z+~3tky-wGJ+JGuz(vG36MJ==3?1q%8R4b~(2;(&SGA6-pDoCQXM2)s>BqJWO6j zuwdW?85}lthj0ie9j}P!r6RRd+$(3M0>z~w^H zh>q4VJv!g2#|Jy=isR|`XH1*h>)a^H4zOBnkG0&z_Q5^~RAweISjDLAObqA{f&~`@ z_yYh3H#KB}Ee-FhH8AsYXS6Eyf#5X>H{d@#)I}|D@}|sfi+K1mPsKwi|p^`n+Vm>+aVxRF{+_L=3V;v3ul)^m)Vc-mx8@_a9)~D2+82s93{z zu9?gC4ifk@J5IUWydaUD>m!bdn5vE!s2lB6IxPMzJSN>8uApf@Uf20*5PwJ zO%XA7KSuxUipu|THFd41V3zXzCb##f8)*AWkKl7?yZ?>hhtB7D?f}K-cIwFE|4r6E zW90>;)(S#69!c?BITqs=PEV;sT&8fqJOn-N!tczB6eXCB z;`WRiu0}C{U2EVip^)eOxe?;(dJAy@-eAKz4eo?IKoImo=XJ+*ftb1%9E6{hlCV-| zv_eI3yt6hy?F3yf{B#Q|%JIi&YFPb_)il31Oz!i-tk;v)4?C^=yc4JJd7s;YmTcq; z|9QOM`MKH?_~b+QJ|o|E^##`X4E;RMpZNb&0Wy}4h|E?|C<_WD_B8tB#4=flmVrS! z37`y@Ld+B*kRybZ0Oid{uxIb}!r*sC4k`LV-byPFLZ- z=*3q1Ks!CHK3y+jl#fz+nFph#=goQHRbHWmSZ`b*1UQ4aK(nbE*dn9f4yI5cyQ+XN)OpNulOg1V4nWE}3m?|x%1tW`EBDK`8?=4A7&-OsW* zpuxvaANVlxJo2C09|#Avoh$EsXV%xh`NMiXcz8a+5POb1r{0GV?`|*bnZ7dQ$Deus z^=TY^vE=`pnG$g3D!{vA~uAocH#Aqcxm&jG6gu=c@i@`C}I{L!CA7ojj3_I^B`U5Y2 z)+s+v{0&eI43NY|49exW7hiEYpFQ>bZ|*wz7@+{#ALjq!p7D(7sRo$dJ^U&PRipmT z$&X0cgDUla`S8zSkPSkA+bz2+W0S0|s*;e9irAOY`k&T2_M~&!_5+1`zOQiXyW1(f zzAgj0m@gNm5Kf*OMJ`O@qIcbL`k9!by|jV*iNkWeVbZuKZ=2F2YOC=tp+V$4=AmT7 zcVZ|>pTH8{{jOh#=M7>;fhzDwon5gjcFW{Cwh9@t=D`)ZJS*O$xWFGJlUu~3(b7|? zIv^iLGiS7=cbtMv`&zo|`4v(od;6KkyfKES3#1iC?SgnA)tVpg)Wxqn@#>gi-Itq} zH>3NiE5i{bi{~94U_823a=lST~IMQl2_7{f-B& z_rH>N@8M#5-it#1G4l|ly^v$Sf1E-+ARy>s((3@l1KcEqV6|GgJSeVs8x=r;dwkBX zaM96jfG5s?^OcK1IMFJb5k4)71fhPXP8-vp{iJ77q()gH!=U9>9B=l%sK02kZPSrH zV>R0DC_NChK-stvVdoGK$sYg_;2$X_v!d`efm?ntuL~7dOi)bE65wYGLTJ;}$rSB* z>?*n1FByI($2)NEZ%LDdIsuZEt=Q>pXG3f`dfHZR&Tp(9E*$hFOA*@43Y~Y=DuM`C z@Pz!6wF8rH-=p@+5@y9NO$oz_4BC*L3(>>YY(vjQT%rOex@D z{Y8>8nJP^HpbKEM9G$XxA%zDvb^SexXr$#aVBzGl&D?x~Sgrlj`*Nm@@tH+HdozA9 zHhkGypv_@ZrM0SzG8zB63;S@`RzHWmRiUG^(U-7S&Qs~H4lt^JT#Jf2H1gn9Lzt;( zY-~NV9aTXHjRb0HnIaBmr_%@{fs%MAA+vIDK=M6-UJ9oX>`G9?!m&E3e+&v8hcR}B zxZGr8-Vu9R)%-o3-*bI25H}xu;h=);;pq0I(FId2l_%A-9C2Ux8di_NW?Az2+AJy=OtnZTUovy`!4;$7OxmJ%lbbwNbJpI><)ym4jfz;rJewOa zxLP;e-ggp~mElny9kz%z>H!BhvpI`bpIatRDsK#)kV};o={K4NrM8XM(kJTFA_CK@ zbK4YHfK}a*(+V~5qxqd?LFy2E2P(!PvDdTw^P^987sJGWnDrTEz)%eQ`F5L(_NH_c zEFJ%dU@->fv(|x;ci!(dabmR>RW7I4+?LJ*x<5|zfJgl#<;4M8($RR{kKGJxJ%8i5 zuDp%Z9iTr}+mK#!jG65m>Y|nA`-5d`hO?AfK^9h^IHvc+ToQ)=hF&<2 z#VC=zvzLy`1@=X7{aDK1Lf>`59zQXdJPXyq`9=V^S(?)APaZ4h>@)4k3G6sj~V zJx%i0xu`0iEAI}>s_)WWdX}k1F43d+!XjJmAhY`K(CIllyDRvecP*`1D*+iDa10Z> zttF??)zn$XT|f$?cGr%<9}8Mt}PcYy)RA*ekD+ zuBEInYxhgk8+V$XoQc}RP!7$@?vppl7y8~k3d3r-0RY>r$%gvadaLVkvDkjJO0v%} zTv9J8rI91$Va*X??+`yKksiW5J^a9sp9soWhR{==y<0X;7glIh9#(iMW=Jo5!Ij7L z8iaHnY!YKI?#Q^VH$hd2hCME(xd`>gO#nEwBqr`7lrd!EdU*H~NSWd}n-M=u26>P5 z(_Tk&gq;UUz9-wnXAvyt5Toz3!~KU=WQJPPuegF~v&o*67(ng7DsHnfqzGcHv@Ry5 zE^8}fXmM?~tU?4Y%MKMu-rSuX%x>5r|0XV*od2Gq{6SPhMyT@x^S3E2_)C^$5{Slk z!zwG%@%>vx0=&GLqf#4AN^$mxZl6#}m|+S-djYG`2iAG|hcWbddT>U@(XngB*g#;9 zJLp1BpwR{ zg80N{O5#gy3SK<25F~Lqt>W00lW?NBgq5LKRt6#e@MW;pYlRC})yNyCoREfyWvdmy z;AJ+EGAwb9R?f7kV_w^y19Ej!nierZStG>Yf9~2`94PgPr~{O{4C?}2%7lPx-u1h0olzPK2E4QA*F_>W;SZ2 zpL`0$!bzZJ6i{ zrK%F2DpV^V|IV@94{3VTtZ-~I)meSA#?bH!C~ZAB2aAN6HS8hwD80p#%G-yLd)_Gk znlZ5a6lx)@8>sh;`!ZH7wizDI>7wV;vDZ0X{D1XAJbhnckLQHKtx%2#10(|9_cC{4 zgt4pe5igb{(Ufrxw?;j0*Nmu0y5{az^!cfEGDuj750vX3AYa)jRG}=aK!E_|Qn~C_ zhXt2!eW;n49@1ne(|z`BQWFFZB_T*4&DzDUfwjgU%GF@S1YRrAmB)F`#UQw2!-phs zLL76mO~9xqKNd9HU7j0obECRXrBe};NnReSal$n#^sRCAHghW%}tf4WKklcGZ`b`2JzrV(G;@oAZ1jXIsA1w0bl+1UTf zZFF^?&6yDqP+<%;dD{i#m_BwI!JplJ$<84w+3*^+D6tiDZj|mN9-rOuqrqpN1fv<+ zt0HmH`8vL?<3n?2XGQwWGo|Y`h`KsrrcPzB=CkGl$3yE6nMJppD;h#ias38RtiLFF z8?l3N6_$?bA>{J6c7wHP9O%}ZGLxMwTzYNwcy{gZ=#^$=jb>$`LZP3Y_H%xce#rZ$ zM6*MkF-g(TBp2cyFV`Sx{T!NHL@&m%IrWk}ylORn8_;p8kCCo%gKOeuG zK%Lm}T+pj+(6Bf!bs;EV6Mv+=9uPuaYn)=Pd_9us3H%6lEE=V;;D$^E*-2OH5YJ0C zP3O{kRtv-S6FNZLsIGp?)$+EwtX|biKZ&x<_U)v_dw>8ywurZd#Y**E|4%|-7O`mz zg1#;O?oBLKW{_av<9ffb8a$io-eIv#oqM46+2=n^s>$0iT;9WA zKWKtVgiF9M+@yI!deSTO6!$raN; z9Ef4q3+TX$`wy7a>f#nhwBWo`x9j9x?jaf=Y{Ac`ru`GT;jHe72q7fg*q?nLzc9ZYm|%MMb{0%L7n{U{LX;t=NZa%*r9w>b9rFhg&tYNe z=NP>I4*M=8kQq%lAiegiF0HD!f&1~50JxnCK(!`>@x z)3x-y=63FWg!cHsPq~|fauw(rKjnK5OrPV}cTzA$GMe_AKF=XKH~M(*$If-r`C#MtXSM1|QH;3Yy!-lD9~qk?@1E@D1u?mHM6|){U`SaM z6A|F&WyPvII(Ken>=}gKap*+KxvV|FSQ!I<#tqP@8#YZk>hlpkyMJ{dB(vIOn@1VZ z4CRL(($IWAeFiH6k;8h*oRKXUpHvX1N-^4b#phA}sCpD1J=k>Bu2{(SynfrYiHT2M zH~txilc6sr8@>C}3vRJTjJ)To5Z}F>$Ut0|BNzvJUGEnTUxfpQ?mgx^T0o?(Q>K5QG!q#936TG zRe#1B8tXL8?bS8yiTpck%EJlg{;nD2aYwOm&>%q-C(tIpu0`?L$L$>t5RAi}6q*Y@ zrGJZru_;p&kVUG1Z1buJz?`+g`QOhUJ}pBEz1LoOvi!>DV*N8B!kqo*ft#JmOkONr zI)db;9;@>KYw1RPy`Z88hIsJ9q5@ILQ-i-idO_Kjac9+88%YTqRp4Z}n>_e>0t(Ix zCznN|P2#QC^Z7h`Dm>Zm6xn0BeCd%9H{Acu)}wr2Ut)_7;cG|IqcId&#M$wA9`{;Z z7m6YqM#vRTsTygid~D?03{Hm)74SL$!6C}EIeTU2#s7H2HPCqH(p%q29O@ z2`&k;3ZwfqvNt3XPY~-TZlLl*(OA`YUyWwS3u;D4A7s79; z6)i_=>{rR|9iyIjJ5B-KBhynVtVk(q{KGyJnILJH7AU0F{YO+r4ArwH9=ZRORNIl` zD-r?utXyLfP9m2ifOS%7#;ol@7jl^}=eZ8&gBFE$eJu8`0U$M%`1XFwqf?!-$5B*En_ifp zEI5kJO(;?EGiqRj-rfAdZGvKAcH-dR^6CKiS~nb(?~C&}N}n6h3UCXiK)|0$5pnRS zZU_5wJxr{=WGZkue34(mk~F&Ed+`cN=!>Zfd2p<#HjDr(`mMnA^?0LHwlCDUJIuo? z441JuA>(*aBYtt5B1gG2NV|-udBpGC5HJ3(>vb6*<+r|5>vp#_{6Raw#>A2d_!NZ% zZELjnRqXF~FGMO3G>~x+Gwm-=*p?X`1%91t~OHUBvD%iHG#PNYPFyFkU zt*9u^U))oJEjS0mro(^GCzP=ZF=P^-I`xJAGBBOFYavpv^(~)50g}VCvH*GoJ=TFR zI$N)n0_vvZ;s6W9vuYDOX2=u;bLwn4>2x+|_)dVym{MBPVU^rf(`uM--) z-?h*k%b4k_snG6BU{|H~l@Dxb(TJAzqC77{ySZpsu?1r^y5NoeZHOC$Ud*KNo}(rk zj3gy4zmzOW(n$i8*C|HKc^J*tKUE|4&uyUkQy7}HmiLx()zxG^UiOcyM)+Q)( z87BH3$bmBk(jzlle6MoM_SORn%MHkg(6982=jFbpt*^DWLxh5dL+x6$d@Z-|#BJH^ zV#Q*GvCM1sKPZJ3Ogup;pDt&T+ITJOo*>*dW493p21+C$uU|Hk#oi<#JClDw-ybsH zoa=h*KX@CKdFQI~=s7nI>@$tX`4U+8YAp4=e3XfAM;8y20jk)0(DxaAx^(=u>pz5j z&aS;Hn^9SLr|o02{U2L<+v~1WTGnGmE{Fm7a%FV0R9?035pYUeR9bf7Y{lLqoT)g7 ztt~s_Dsbr%S_*mXceE(-l|AYJZbZAc*k+=xF0*=rsmjqdX0%_G8ljtgSq)2NGGVt{ z$abJ^*W3n8t@ww(O^B3_%pr{T0gOr%?336!>-&%VZBWFgOo6kxFiRsFvp;A{y+mB? zz_Sp<8!k9@8)C9C!VW-PZUJAycbw_^0=D3aN&Cl)gz6;! zjS(VO56!Ov0Ir+EQO-pIV6Y^+ye;4cte~p}Z9BmECkP> zU%|LPxG=+FzS}%r2lcigg`E00deoo{zAQ2O_(8CB;JtHddv-g-e4N7(XTxV8&E<9) zf=F({k!8d8)$&uxFMuF7`>EM$*?SFsSUjAi7_WmjK96andFv5J$F zzU>?=UP2UBbTeAVn!TN<7NVy+tZb5F_QVMTnb&3@=+t2f;nAe>%Y3~^^Sm!)Mh+QO zMe_#n-N`YV^VM{0; zLXFCOCWfDoqLLNg-%{q`;@()d`M+L(rx(Ri!oCLh0=;eoN)A_;Ai)`MRFrjGzKZJ; zW*kv3^UQ>8#9-s&EL1V~=oh%h{5RXH`OwgzL3e*M599i!5XV9wld9`+A+5AMJG zcIy@1rVSRLinKS#kw9Gjo2c{Zdlms>kNfho%M$<@jAw54T=(q1pe|#yxg8x|IxGzN zU2{%Eq^ju+QH31W*fok~BeD}%z61L8zALv{c2<)dWDg0Y&1 zTUdr$NY+*~lV|J0R)KYzrCKp(?9P1gl30B;F?>S=3*8eX86>yXF7G&px3AEl4UE!A z?IMiS|95Q94r%DOkA6`JSpjO%Hu?N)KCIQvUYDyE7E73u?>LkfYwj?nmS_kn?YFKX z)X>%nQ{gi>kL7uTf<<+^|WhM|hz*yW-Q$@1cD!ldS(Dc~^qKJ;y@hZi#6|JWtveAWd{6Sk< ztj15x1s373U<(C)Jn`}a z*Va6gARk=pUkBbHxg`;eoJGeU-n<^^uLtPA-9Cms*?CYJ1!4J#?>oQCJ>LN)27=fN z;?Hl-kSnJ(pFSCBizfJL#AOGD72kH9<7v}j&&9iPVUeM@COOJel2?^GA-!MwelaTU zZ?D#Lg%Te#!_%du$>x#y!HJ`}{GvOBoa)^Vj+y2pWCJd*unRA;vlXhJ8fw$dJaqok z7Vla7Zhqy~Q-82T{{Aujo&QP)imhSOKCa?*V{?l~o?GjMzd+NVeEIU8s0_d}7POF; zPNXvgl+SAnpmN-@RV6~NYm}1L>wAEW0p!B3G&Fxo|X zhN`!TBO8Usfs4$PSu?<%VUw)*)iT2P(`2iTM6>8FD0r4on(iZSQz-a9J{$NO?b(e(3u#q-6o>k>46LGvL+%cClFt+QLy4fZ4Nv+ zo6_M?;N&s0^PKTOgqKOEL75F7z10n(jPbx_#4X0L5``POxhW#97Vwr-Ekp)<<(DAT zVwILpv;Xjl@4+#s68B$)8Ce4;%;Md_%NFmlI>rtSEGbURV#kX8PlZDiawNxOIwfvl zDMZnU?o{Qv_+vYPQ_!Q`&C*B6qSMe4zqd>W-lfgF1%6MK_iIn6#%K2r2K#`wwc!)zpM4@BX%#;WUD_ygVA+Aj$|ZGIYJBDXE9XAdp_izmiWr1w=Dgp z9IclFx4wV-+deTF9or|6bbUt*hlr?%g+*$Gzju~2%Y?PDW&GQ;@Q;OY7jGN`m+k%f zE^%qFXKkEkmWFAlDt+M?xlK`ZB6gvguUrM{jMCxCdX5S_pXSbum5o-C;*W-buqo|h zKHLzzJP?82X!-Gj-iw-fpvL`+@k@m7L!&}&)62+q>=v6|#xmJpLL17fanwPkkfwg= z2lbrSr0k=16A7E=GaSqKyOgd6)aUTxeUB1dE(I*pRMA4#`R$;Rm@-K!?NR)Q>D)Wp z;Z3T{mnWtv?j_3b0yLHYOF+&CCJPy-Q>|L*^st`r|#1oglFNC#} za+`_Eg%mK~i{D@_{7n4)kzcBU(g}TkO$nzfVw+-EGRamKfg9F&D5|8*Ihsb~J}OoZ z8ojXI5;7ktdt@@0^KWL-xZ?p{RPi@KH9qTxmV8hca6n66DznDzTA#sHbpC#;0EUsc zX&+PZ8kKp-A?N*iVV_Z$a3U1}cz^6KFz|a?KeQ-XBXuQN%QRT<-{QYD%H?mJ`|xe7 z%mnmyKoN_yM9T{l^?0Af#R&T!EfG?sL8VCpDmX^m!Fc5ArbE1S#zG$=YPdE%yG82VNhyPg-LfDhFKEOa-eVHj4=dYKxSJ`p}0 z2BfC_tg2sM8l}9m_rwTa4yMBhcEQP>%+uD(?{+x=I>zM*-TZ>m<}9^LSf$AXz#4d* z+{?(8mG}(XhSU)RVs?@9o&Ls$!5=0zdJVfEQm%RHrhuxQwQG=Kc7bi)x(yCW2RiJb zg=%}$g(9S?rKhrhoh>LYPXN~!<CO-z?` zd196O=*_XsAW(Kt_gw8grMV7&aelyb#7YCY$Nz@=2(xztEX00X-cIs$m|RdfaBuJG zR&>5_&xG-_5gYw*7aoAsUf86(ny2R_A4#~A4uZ-HDOFqJ#B$aA1TTy2cifnNDC3Mx z!X2^UACasDv>pLk3D|jfWc2m*)t6k8yJ&4vBi+xqZbU8u6lYCK&&voQu;?&PXwo#B z&uz5eg+TXF-$2Af)3TLuG7#^}ZvI|8yKe6-K)3joZ?)j9C+|+_crRl`d%>Ig4!OWQ?&0KgZ-! zTabbi6C>vNVYln-WaNoX3(Lx9CX}3+S>kBP32y#suz|>K-8gUwC2~?n2*c@O3CpAX zhaL0xw0+P(AdEN>NYl8!bdx(%M(w?T{A~Pce}$!G7!57e!prnM=bOODd66kDfl*y`?iAUTW9*abFhJH z@jsun>}%Yk-zK-S%|PU?Id}JKpAOq+088*^O!R?EJ&C`RP(JrkGg{{W&se`ssHBU% z%PD)sPYfKOvy>OCFF%XK*i}*Zi)QZMzm_`ZTIEZhk%sQ`6Au z>Lo3$=Hy_{@VFS>7(P+=Y@qpfpG@MIZ?@ph7#KwDeGufNDScLW@m5Ort^OZwPd)lc z2y(2XBC#=>kFT9y5R&o`q_k4yrE0mUlNF*CCB-&EMG|jF7SyB!*#e zj;{iX0T|YGzX;IM+~Kw`?GKo6B9t&^bK+*`S&R8R6=0&Y;pPm{H{s(1K^2$E;*rb5 z!I1ncHiy;bk?WYY$D!2Hz1b|2I@RBu@C7(g@_Z~o)Q)g- zpO1k;bPfxC>%{d}2kSZSwk3$a67L1_cOm=&XaeHXKmcU-cl*zpdn0?yx7}>im}%_m zUX|Q7%BK@t#(AUlJwqO}K=*7bTYYpHGTqulcaAEvn}S_ZBxhT3CM;(A>@?z|X-ZU1u^hx?LW|`nqycKGY~*uU}bS zY#_=Fq^LeG>tFdPoX!!wUwUhEKk+JGx3F|UOMz!!=lmWfF1OOKq_=wn+eDNE&py1; zD2!K`u`Ds6C6%f3;{y9C52eBgSB1x6ZTDZW=gZ||v9UXIL!!zEKVwR_yZ)@WZhj_c?HsAsB_Z#TM@1hitP!r;bDVc#&?@sIKv;k4-vPhId--)_A zEE_orh(dP0JV@F4E?HfiDPIMA&1KN*s}ELKAtwi@ciS8EE1@K#>`6#URPaFqRC=(8 zPAUtju&@veBoLs{%*=B)td(w;%MG;2O3CA1wKP4`wrEE}!}E#rqO zS`AL+pk_5_@r)S3nJ#2sJWBQyahN;=5!+we z<0W*ko0RunP~d2$#jRHm=rz^-4y_M>v7=eK?0sl)HI>OERm3H~8c zhd711z*7Lfbn_iW*?*!htMm}xAB~1rE!vBh?>~mIrqUhH}FwH zl~?Q=(_31bx!&GY3moU!ZFcmWRhP5c4YU!(sKoL?FfW!cF>tbTv!c8x27$uqobc*o zy*-cr`tp-^x+_2>u3ymrgm5xQ^hoG>;o8li5>r;Gg)Q@n<~;0|FS*bCOUC6D^bR-8 zH6s7|TKA<*-_hlxiFPLkto>^bPOfwNG}sr@(+fSIEM91b=_h#}2LN$|* zs<9QTCuDwN;j5Vq$im-VooPt+eG>6_)v}@^Z|LmYxNW~U7K;b4OoL2KO{<>~ zT{2_nSs2Y4KJ0uXbasF#+cngJb-^LuQ1FYP=z!7earm@~q8b2v1` zGf9}Uk0>^F=hk7j3WK|J2{`V`DyDbuCcWTXM){41_p$yhnz%*Td6_=Bnv{*p0;-hh zg;v`Z6N#KKp%>HE-a^Xdf|%4*3XAJq2+o4OOr|*ETEpRW7P74S;>n#U8) z%>^k@VZnOyb&Hjcl#H0IUcL#H==wSABaU}sjqH;s7wrTWlTgKOn-LFe95WRb7zMKQ zje2@)w!&R#;{?;Ny(6yr)vX^!0E%?KH6!Nf@heYl$oY`NZqL&hfL_zG&I1w=**e+HZDfdDO{2eC`ge7@eBkK5jQQ@K$X; zmJz0>rr0|5q3XAv$B%AAgV${p2@GDZ&td_Wd1u?R_e2!6E9nJ zdT;OBZxg3w+i+XFiYBu{XWZ478yzhzE6+`}CRDD!(=LN{*u^t1c!Mo#h!Xe|Z8~TB zO$aP<_J~~!Cd8NC1RdDpb!p4>z8xb7smz6FODu=z1CWaNP412`gn~FjW1p|84p2Q;ML}zgp_i+{cKXn zABN$mkwSKv?oT$Wm9UFPO{9*8lA#IF$IWzsI`Hw22at~k#xO@2>;-siheN=04?A@% z-^pbd z{P1jnSBSs3#;P}SgNU_q)Yz#DoHPRw;2Y`7?9@7_&vaxqe+L$6-?o<=I z$UC1@h>C}c7sn)*4t|s#6+;3E$96N^G^OS4*tZjL(E)^OHq`|Dh81THH-Z{%i{Md5 zasOv(GsT%+vY6KQDNepZsT{4c==3z_Nz=NvhOX=NQ9DsemyGxAsi8S+_iq2ha)@y+ zWO*rnF$9>9^p}^73f-KdULp)d{$}+EBHa*iqafOSD{mUEu@6iM1=BeK9=>h*#{j8} zgdM5j6hwJZ_cV-Tsi7-2I%1L~Y+kIpVLY((rAV8ERGi^zHJ&Puntfcl8@F1Dh!X~w zAkse{70w^fN}&=J$wcQgkcx>`V6d>T=(V{&f3CIEdx3(2w(6)~g;w?S^z7Z>X4fgp z@NWCJ>HQ#U+Ek!KQ7ugUlT%(!RWLi8JF9WkuB@!hbk@X^3YgTCJ@F2=xDQqJFugpJ zX5+98xA*XHx&@JU%HJKq{O2!^F>*sj!Om=LEete@ebeY-Q+tE7!u7vwIC=7p&Z0Gz zJeFNGAOo+&=Eb2wUe+etgU6ap!@Wy`YD^}qUj}2MjsqvcnAgs3Rl!ha6BarsqTeR? zYQA!?1U4;?)mzh@F%8&8=&q?AnXm*mzpR!imF2&@X~Zx!V?RwRwjp0Rjn~;IAs{qM z#rl;xW=DuvD$~Upr2%Ku)-z;e>EWhlA45t2YW>plWE4d+vl;j>8e@W1L|Pp;-OEW zC$(tLF>#)S6f>>wWDwZ`Ql25w4KyY8WEnx4E3GpXyyKf~%c%=Zih!x?s0UL60v!i_ z#Z}D)dZ_UOwSfmb9D;>Y5)o9;|33PG_g^uJZj+@_+T8|(!FC0lyQGv-Rv0*8TtMa* z|LhG#sXsjTkEe(0UW10G77C?SZpQrcyE7tcv=}NJ(Ky;`oJO^a(7FUrTrDQpGl`>G zI?~K998VHa(3rutpFX!=114)g#JgSfX|B_o={4m zXk$u2MBhWxl1Q6!osx+8^AV(qzJe;&5KZ5qSYIyBErNJ! z6i7yGPQ)sck%~)%3paEmkU=dhM)%RPL11V`5al8uLytRctWlAoa1RyUaoW9pt#^Zr zByXrg4o*p_B>(>;)O2%;S_CGzf~kj)m^`ZZpXBf;UwyfBEvez|a2LOLlwCqvC zQQxbva@=U0VX;a_3=0Rb8Xc6PBw*;oE-<4MyU_QXgw1h7&?eCCod!XLs~@U!<+X3W zJ1%Shn=aNNHLTTPEjzy2ic{FK=k{Kkr0e4Vi)+COJwVw4#3O4=x|Y{MXsRESGBo^< zo>ru_me=8$NeXUpGQGdK7H22m65O~hymkcY4OCc-A5BZ0G*h6W^%XsW>R4CYcM%jo zxYmia%RxE@6<7lO_)0qdBb}TBuhkaY=Em~zCPnyPmkPG~QxuF!5b5Xe1Fd8v9@)Pp z3mF2;-?`5bf^vNgMSG4H)oA|e>tN3A(nhoF;<+=za=mA?Pgd+l*!jV+F{ju?&mif0 zg8jUuvF`@UZo>KuFk^8`G$VV=Vm#no z7iIL^RrIX%F;po*L!2sk=-%!~QA!%WH1XsxcjefBn}p_enP}O^;~E};lwxL)tC0i; zeoK)Qv;m#7Ovb-{VYHE(Fu@_oAl*;y^&uv+AT|-3jLI zX!KBt{M6a(55q{t`K^LQ&<@6*QSS5JIrxx-?U5fSN$V-Z_WYZALME;DCOux&8@CoS z&ibVKCs7JTYK>o~*$>4)3_L)4&6*@x6(c^#H>^Gm(x1tPP1;;KT-8%73Nk76kfI|PP6W8;K^9I+ zTR1{|gZIJL)$c25&_HxWj^$oSkIXMgdx+@rVv?mLU~r4WjT#_5ameQ(H%ZK6E?eMQ zwZS0S5hk<6g0{XJzJ9?c^7=<~0O<+IMi7xf3C(9@WC&6X?GA+3zK~KS6#g$ZTi}F) z%p3;QyJ~EOZ?htRH;&G#33g+{2z0;>FYn&-WaU`bB!5Q>aEBlG4P%@If_ z!-&0=7zg1qlW}%)W6AMLWZ-2X$*Xd(^0iUsP6;&@kqiBF1bwjR!-!f(vy+Q=`JG@R zN2gx_oXtu?vOH*DmuMZC2-{+H;G5jaStQrgsWp}+u8FM%i<$zPk{xK!rk6^db;|RG z5Xo&iPVjn&8+)Ds)!K#%#SFCZEP33DvsRz!;ulx-Bxl(A!k+&3#rUHq))6+QQ&A4} z!zMSfBJsJVhx|Q9I<6&Qj=|vrFqdZI#;5#Fns}Jt0hokjzwB*L+{^QFmsCoaq!92$?W9z0WngM&4vnQf1LL_vV7d+R?xrwudInU_@hCjK{U zEyIax8L-y0eC#;DHgeJE5Y7~q=V%99#q>)hy^RspD#?dCvF?(-4}iBeuIVtHGzDMp zY8$o&Ju8obgF7Sq*9-8$&=*&lxjrASzYUoJMl~a(L|T3}vXq&-c3+$1MYA5qPazTd zlf*_gWXIi4q3g2r^`U;6j{Wi3)9?GD#*K9g4_|eQ(|LHjGVGULzWDCi;0c&NkW@_1 zSlnWz*teP%sX=QU8u>i%cR#oeOdG!FV%Btm@D$U%`iole`erti78fHdNXE?}+ski@ zmMtS=WD>JQU;KO65vD{M+mkj@`FU>jgN*@})khf1e0GQ%8{y2#Wigx!8IBQZ@jukm zcjur!`{?29VXbd;-w6|BdKbQn&B2fOP<9}ik$9&TvPIe%7!zb}O1JlMZmBF!dEsZEah-K!IWfiWe{L z?pma{ySux)Q=qs*@!|w`cP&;lxVuYnf4k@0d;iBsGGHee?6GvNPv&fK>-4+7zf5RK z%gNaX73Zw2oF5%+owc3Ow7K!$Tp=O?q>Qq5Lsr&`@7?O|JVWXE$;nPO!VM62^QDzl z6*m?=4t&k_aXKc;{~d#T*0P_S&=46J$)~8WJT=wRVQO_;!B|Ovi@UXY?xnuiFf=su zF!v6{28@FI=ghsU&F7^bdi`;(2?7Tne+QdpR!&Cd0;L7GU3odVKjZ%QVdF1>fskug zh+PUm#@gfJqWeA0F8DA0{(@aVS%z5^ZRwZUS&X-i>dvZI{pSIF=bt$=4*bi& zyD%U|K@@pTMFXxCD1Qf(72Vely|QZ#5|miJ_A=6#<7kCq^9>NHl5tSxl2!{WwH2G??*yqU;I2S?Zao9I1%xuXiSC;kyTA6@%oE-K;QT?7!GlBku&XyMQR z>70_zL{Y5=ML#(ezG)qtglX(aK*891Gy*;=_sgUHzN-{>SDqNH1ymTz<4*gf ztRImim=R)=k{(uHG0+f#HZkji#H*P!(w^y3{OHiCpes~+$z`>3a_i`otf5PeRFX@0 zP}}X3b?6NlmaT7L;fhA4I_&zzG9rCMxxJCgjFsuE>hZk&0|XTPYFlR#Ao>jV`ai@4tnIS_IkH`o~SJg#0J3wiu4f z=Hz59wjvqrD)_m6jdQNIw-CWW9~>Pmt@s0#X&?6eU-!pfwCy_6=DS{R$mjhofs1-V zr@$x2@J43mw7c?ei!wa=@YVoxWvbqm_xh9G_zh#nHCpWMk$vkS#hM1_cI*?O_est8 zONLz5Rb?Ld+9ZJE?*SFjCMyvCV)Vq#zU(@;5VRU(ix0gHnvvu$Dj`l9$7j${P9^aP7 z(gt~fVPN_$A_hzNiIUPNr4&DEZl0Ru(zmdD}p4UBQ8e0Vl5)8wP-TwbsivjkZBa#ljuqX4{}3 z-`II=-_zblnvNeu@bdhsw~xp17HlH}k=UbpUCqre_Fd65H`3DDT{&vnZPktOH&Yf# zk*N%}Z8kvOa{ou7xBQc(sXTP#Bar>|QcYf>Pl~$Q$Q<^(oUH6++Js-@UPEzl@#x%n zNmd%j`ZSH_2v`vw#>@q!>9CBQYDb>(EFh2ayIzk~kN-r)#LVdk@^GlFFS*Xff?ICy z?>)wEZf1k9ep*%NYie$`$tLB0>2m#WSg)AJq^NlZpnKi7P^t=3cSLQSwp0O;bNt<;vg9RVp`FPh?vIU&*R;E;2 zC>TkzvX^m%=42#~ZbW!tK=C&f#)R-TlDg|e^LJn&AQ~ti%E%%7d-h<9J=3#!JM36k z)?%*Iv0HOoT2kCooR#o#51Q2zKi(ZY`qb&BwL(v2O8QL~k;GL(5s=~9cZJ+9apxK5 zx1ATu&Du8oR+22?L#TFy z(Pw8d^EQ{*?EXwuN*R#ef^@9fuQ}OOck6L|URDPj5DAcHbCGM$xXS5Ns@yXkai&~s z^E!(^9JgYRhG2eY_v_B9BbQ*pA?s`$IkE~aJo*c{^dK!*XzGx&cJ`0hnRFYVf@gxH zD!R4O*2PbeU#|9`RxG$jcE5qy$|;Cb<^)HxPN}L0Fm*#z2)d-xDT-EWl-XEhH5~H? zZ4FpITlal8@7^mpZs;q-P{a7xSNjs-M6J+Jpi-!W8g4*Q2B*|w`~#9QMd0g5YqhS2 z)6UuQszFn*Gp*rl%of-j`+hM;CT`qJdTnQMKYKe&@cA=D)4Cg8mG|oL2*cZo^TcJa z4t=+6)9ToKFU-4N~z2YO#0bnC7)n8T(JZ|E=S(7F$&6x6ozIePn|7yj~S3 zDwdP04YFf__IFpKrcd}P71hv;n`sep_^an|pV+A#bB`2t zsrc!@1NB+eFDCYVkNy01ncM`Y9h)%sniDjv&*QPN&%r=?q>V*raK*0 z;8yslq+%y8b;Fr6E4gJ#8A8-ZS&9LfNLQB`S!=1R@lENk?m*;$Ss2LEWb~G3nv5n{ zS`0Mtb|yUK8#QsiFro*?D0z~*zh&jcFTab&qLAzsA+pr&;5{r@i-vQu< z?5;d?D*KICWhX$d{H1&-luSHJKlJTbyl@CU(*~THV>9ErpV|;NYvcEd^Be|AFQJNF z2)L0X`FTpy@@AJ~dcy2O2<>l{e28-VYFoC$LbW$j?E}^j_&+oSO;qNn`}-rmnnLx; zVkEA4Vd!y|#A?QDS8#u_{3=cF?=L59I=&@H7}7+vOf9LawThPe2Mz3Abx_sC3#Axy6jN^j_caF2_wr+m-Ew7PJfZO*k+kI4G|@yv##E14m9ZPZgGz&U(ZUChleV^ z;Xj8`=00L8GDT}VzCv)r$>!8mZ=h<%l(>|yt@>V zXjR`3*d>Lw+tB-rKh_jvkKL=qKdi{T6)H5gD?Fg95J}vChXhlEsbg0SWEog74H|`1 z>)ryjx-4z=8ba5s%y!ArSPh#o2dGMiKTYjUcbp`o*kGlO)SA_xMGjeG*KIMsuuiW9 zMKJvAMP%yu>90rU=ldeYkWBm5(Z7vaVe6aE4k7g3%GS&~LB%dfZ`vvjU$=_dbhdh# znP-`K>A6G{NiDTBLb{MplXWs^e2di5IbQAk+Hfm`CY!Y7az5|y6au^mizFc)1(}`a7KALl$W0VC#o+Hb#;%q**<_)1qIBRrvAy(p1Ep($cm`k{P847VHYJ!x=mc}X+O9BZ6})gnkCw3OJA{e_K7 z9bNhM--!&oR2afmm_>kEA9y#HHUEkF zVu;vc>kmObc?P)|PPrzX_PY1d2Y$|OTK$ffqJWuJq1!Wc)G9VBdQP`$@(h?sYxO*h zS4fAJnl>F&O|p*+pS$|EwMo&05S2QR9e51Q(9{smE=7flV=%WIx;Hs2SPeWqmoKFs zZCqm(`rdu3W9m@yJuQ>8=bT%E7#ty=)ksWeg;49osj!{&h93BJO9om+MeZqt7BlCq zzscvztze^`nH8kfWAs>E$mAGPNl>AXqe+|^*crV~w)iQW#_U{`8^|^NR7K3N*Xv27nBg zI)sG|v;(1rsPvTNUrDq{Cm{fAnlP{d&2rEV{ki)OOU)$??-_h5VtYsRkARSe(_?p6 z<4ODL;U4c5hB4^qPEa%5_|~xAZ%o!oTM!7p|MJy|r{}cPcXrip zW;yx@5lt`4at)`C?-ECcu&)R8nvml6!5TTp1gfZrdF}-#_@zXIfJz!^w_b<>@{&n( zPLf_s5|i9#v0b426Om<8PCYNg$gl7eES4`~y9ikbU~p(|D?}lBVQc>6={&WmrnnvS zIz!SFf6Ux+zwLlstf3^emF~D*lQ9l#xEQ|ve;2V$T;abEIx_Top#(H;ssCL5W*w8Q zXK`-v+`7s?S>wF=JCU*)T3eGfMm;qviJg)_qlr=gQ)z?V#f-%SA2~($R8+mfWL1sH zSxLcK+twF*SUMy1t22~hjfqMrVE{}1v@tJCnTFkR;3!Pkvx6f>QPu3^vm8QF^-@h% z5b}E&`P1jM6^b9WsM0-B;pa6CvP6!4p3-q6tb*e8#mP2P&9y~aE(aA{kfk;qs`d?W z4MrOHR5Nr}5Lg==xdZTr?`U|z(sD6MWvtqyH&UBUfxODML%9rF%yg+@%(I439Tbv_ z1gLNUf)Mn2Ny`w{_{H%9-^0FF(hJoe)Ht;|RVfqN$Po=jNt)4ze~c6=4KlK<%WW6> zwZycC^%)#Ou+|mT(>w7y;osz-N<%zw%{Z?Y z>cBkH`AC3D!BkY)t6q;q`)TQBqtOzcHofwt#<7K1FD!|5<6RDclAOw9q!x%ooITKk z1X6vFIZEUvcKPZdw-DwT$iaws$VJmynK%v5vFyLDVVKJ0ko2)fS|C9lb~0J-b^I2- z8kG$9ujkv<3C^+a=IiGc_Vt$Q`(dcr%cn(?}}a)Ea7ZgA8yE zAO-_LWh?)K(0c{`0cGDulzsjm&ok-M+S&>S4FxeaF;UmqsrSf}G2D8y@d8>(ltu6B zO)n&dDXyxzRmt!=JPvDIn(JgwCbrSQ0jU;QrnIXBrF&hytZt_sREM+~GR2`?0sBh@cNW9QEX!!pG%DvIr$!lfzS~bjv}D{wWby| z3nMkajj+A&VM*pxZazQ z9`AWg)NiT$Pt^ZyYhmWq)z$l#*V_4s@$rucAy%b~l^r*8+K1=o>nlwfbX0{3QvS2g z&sP(y?Ch$Ioy`C&ct4cM?~N6}*>Nbl;;|iV`s8;~GsNY*H@5eRw|*}sm&F4UFm6Vg zF+M#tRYOhVdsC*ryZ-jF&Ux&=tL_(~-f^T#K3`dkwPCIQgc~dPdJlYW?E+R0DE(|) zw|M^+bo!hzs(srSK!~Sm#ioLOC`GQpNmqVKK4tEOkYat}?ImT;&XgmY_#-U@3|_rc zi`GSunc&P#7E=_Ni+4y~U_v4pCR?OUH87N=Y}bkOuWMPcS!e@j&D0PBE?+84$n+fI z-D=#8>Um1P*}xB3#9#{{8ry(U*PTVb4X426@Ffjl*@_;oougZ2$%K*EiDMfPn2!GZ z&l=iaba7{dm8e$;>3Lh8aRfLuNDGV|r_n!G^DyyfDGsxdCB(@XZ#kck!=&}pBb;u4Zs)bTJE@ys zQI0EedOB^ISzc~y(WkphDr20V=|d45d$`(%^cdA%>m5$qRTf6DhFp7ly#tW7JDXcW z9N0x0x4KjSRg0y}@u@ZOWxiYY7nJ9_?B9FMSbsJ<>$qF1?ZB8{cU!hyap?O%ZcXI5 z6HmYbzPJG3uuESq9v-dR<^haRb)X{lf|T#CFgcs_%*++HMMTE-?u7-7#hd;8reji| zF!Vy>Ij_F*59s9mGW{1CePEE3`66ccoLcK|1LH?){6;-^ztZg;=8v|e4{*YD-^K29 zLs!rl?rtx=8B*nnLB?C!ecuOh6H`>j#GqLM>LPwE!J#?!a?o)ARc$(&0f&*xn(lmfjgnvb=WA8V^#lq(C{>GNTHF!IuiJ)R_-hp;Z zY~%d4j1i^%RAU#nia@UZC~5s%CsYEBfvu&<4&}KR@5XWTR+U&{+`fA~+q#nud>H!X zLz-D0hjz|hWiwOb?r*I~f@nRQo-=Z&MkcR|}?S=Mm3RyLAGJvaspkdcg%vP1sdU z*I^c{tgL{TG~G%XyzaT5<>Kz1TF&qL__wM$xwSMr`@oIhowMN3<@V6%?H~EKYk8ek z7m$&y9@68V)UGks3BEedhcJQb&u7isF}2qIyR`b7*M~De+U)0z_bpeyc>^m7a%?!X zYi}#;eUHuPPcZU2pH|PEHhV+HUzY8=vd}5zl1{e&?2htw<^WLaI6FPoXya2geqCK% z##4smrwqYle7L=79c6v5Q}HNHdci+cLaUk zcAMuTEF&2(QhsOIRM{<4w5TclBu*yGgio@3Xae4~iusm2wE69sSf)6iItXJC0|&uI z6`HyUB#1b^AVif*|fnzSLw_-Tv53V|AAHC0nC@$BA zcl8?@k#X5t6d$u!sQt3ELq+`Pr7HRj-Jr#%`r z7`AMFWeN23xCvd}Z%{wnu{!gPsJYNdHka7d^h2j-?nCXY?&?LZHtjrgmO}xI+V;hS zach;Cv}D-3i%7~FN9)7mr|paN3C^ynWu8rc??SAfr8QXdPUCk&H_jDlD@*WiPqg(A zstr}p&j$FNj-3yAv*QF8{_VA`QAzs)U+?pYIQ5foFM7_`m9_PAfe%4-I#xd9C9PNL zcL5=iA1}T=*lD&as&75VzLRXX>3IH0DnUh0G#$B52RbzPLS8+6S$)&7Oji(nYT54^ zQ?4gOl}mBc@jCtS?M_1J&D)De?liLC+L2`V54$emi~H&!H@(EEc*3lh6k-A%=Ih#t z%kjE8QG1Dh>RK!rpe%dqysN^TKIW$YAgzYt{VGImgvQrQG-x5N>g((4q~wA%9^TQX z!9fc~uXk3bv+#ru9kJEZ>vgAp&i&t>qU2>A?5@#>o=(@d05Zxn_Gwt&&q=$qm+|cn zwbaZr(+h5Hp%hyy_SGV{B6KQ5~QPb&kYpLz5HL|j@ zvX-C!dQv1RD$3@p>*dsb|5rR|_wR4%TaP}r+}wwZKsD}0No=B*1M!xdxj*&{s-=u6 z-miZc-xBt-mq$!JmzUQDYm9d%zB~;1KM&bX%N0IuElIIpo?sLJ>jW}DQb^7H{{7qO za%(_Vvn+iP;QZ?iG}DYBzEnI?n8Y{S`@6ipK-?p;Wq6v8y>OJ*#yZGNAZ7SG%NIif zc0OAT^ivInia8FghSkE5h(a8?xi||9n~+yO4c%Z+_%wTn)9f`|y~)jcO!c|XdVNnH z{RG7vAdCf|5=~=jw1b4W{Gh>8P=}~ip19t)GF_4+wGu3~x;iYYgi!{xlJXFwMNDd> zsK~a_yR>0_rQ{%i94rNfW3RUPuw~D0qP5B2*#{b%hN8={Vt*Y~C4Z=;Fc^lHDs-fA zFsbNImaOICEuWk65`)c@beR9Vk)|2-n<|tMYWwq#QlZDA!w@;j5^DTUh$-ojGz7r}FwYfIQKcT|1#vHSXxH4`ry~ z;-U|>D<*YI1J$ocN?$zq(e>eJTPyDI)#K`EL|P2<$tsYywUMyzMZ%`Eu*xS3(#O7h zk-+lLp@Ql$z5#nWqZqhPNH%Vyn7e}VmQkn_>lyjL>0IASr2>OOf`H7&E$g732wpbm zf`uYjAlfvQyNmtvUnR;s^e!35DQI@!7VGuE{LC!R^eJotJb3g08F|Zv2hxp98u-oW z`TlbJIFcHp!0#~CFFZS&a4t17iqAR0qhEv=bphY|>V7-6uCet7aji`6#VSb1RvSAK z>G=4V?{39e6hVMZ&~--Ebciy`^RUpCs9L?WqOenA4=5*0mg2o%?r#90-jg75$FngJ1&G76Jsy<6du(#^}uOY`bky478z62Gjh>___V z&sDSTg^!(`odiwZTj7)%T1z~U_iNtgg&iHf&RzE{_dAL5wav}Vo-h1&DM}J^R z8{6~!vk{D9hZlAeBUDpZOgFZgoZXp-9d*wVsH690=ssFW!j zv^HC`wx%bXJJ~q;&xzl|)4&@zCE|A>9$%UNJh)2@-Mq9i zsVqfk{Q&cOw@*$7t`hXaeU+4zQ%%i_aMZYI{tyci_bKoHyz#~JQ6cvyVWfFe9zMsf z0%9QXRXWx$Dqk!wx{3*@3FEqeRfI!2GH2n$aoA1>E+3rS`?JBb#fsK_ql8ZqJ2BhL zH@-yy4A_I0bYkM7lwYDM`<#-8nu@W-yN4(5;a-@3Kr^UXj$U3UH=lWzJ57PyUY!5j zyCj2e(|m$vV`(x8{MiqFz1W}Ex4C&vaio+y zu3@VVDc`S1A{k9mfbpm%ZLhJe{GFemz}xTdmw|m8tufTUGv6*7NA({@)Tig?)&D50 zKksp-r7w9oA7fT|zyQM-;zv=qQiKeJ2%yo@sOYj{B|1<=dyHr%(9!bS-w|2t;9g15JQ6fFvIM6Tqyy>*!Ni z1*X&>6c!m36*sLp_-+Kg_qd)CmzEL(7(eVTjfSE)M&Cne_IZK(jbPV`mq`&6u+G!< zjQo59poIb=V%G{?`;LDO`NATW{T2XL7ns$|(gCoklU49Nf5k=_(`&UN z*;bsxfulFF`S#F>=`;_{uX;n3QdWAcgx-Y&Lxie2?WXe#%~@f%C|{`dO% z4|IleV>n2dg>rs-i2hh5| z4+jDgctD`8ql`f*2~H6ISYZ_C-Tt3$wwYp~3L4b-x-97(Q6-pD@inu7Y;jyD18iv-&poCY;Z*hA@7Kc0p}`L zQnZOv@HcYG7%p3FkVqLk{d4);XZc<90x0+-a>xbd6!mMWdL?Llp3?!U&k~r%THP)N znl}c%%uw6x5~SY1)R_?!Z0x6 zV*0sWf&{ISj{D)c{u%?Dt zJ!&=ri8uXx1%bHFx#?&CRrVin`8I$Iz$1t;YBI<`WfcFYEB|fqHltz7&%Az+dbkyO zIw*wbwNk~MY1AwU&}JDWL;LyS(2EAC;%FjzJX7sXA1YjakN^V+hMYa#d@-M&PN!OV zJQ-e@HO#~=k3^vxnc@HxeLu<~b2%pKWMfTDYc2nP^#4G7(;&FN1JxNrN(qeme<*$` z=8FKm^B5=fDhTTt=8rrTe7tX*FW;UTLTp*@vTnA{qcj_g@v#>j*bc;`C9j`@w>^Ix z(sMRq{cxiFcIy!+aYYUqz_A&#Jr!3*J%LRn`U9`z=}4QovNjRXYk=y|z2jpX3$rjoEt5c|$R?E`jR$Mk*KIY+P;ruGfH(qDm?2fjB*U1n z2p_RJcxpm}e2z=`I2xrjwayMlUzM%3&Q z3w0F{_-yEVn=6z?!#3i7CO0wM2a&(bN2TPS1eIFh2o)33-j+k|{|K{Dp*OwEyHT?2 zejtGbVN2B>eJ6K8J}+6iOtr|2481DNmkHCfUYjW~BfgjjN`h&D=P_)JDAv$+HNE3Q z)@6cCNU7?_ScQC2@s_rvUgZZBv`u)KrUhh-3Y(uvtdD9m#1P8uxORh-*_-NVmvpGP zyu-nlqvQMvga9c>_!IV!Bz;;NQY_N-38&hKnMR&WSer|xJva{rEC3#j1N6{-S?VXobn#Z88V zJ0ZG!?;mjN#i{CdJ)m0}_7@)JgXPqXF(tsbp?=e&9b*AWBd_Q=UQcVu z^TqD)uE%~2zKUqc&$9*^d>;Jff#JvZ0VTHk@L_O7QrVDR#I>bKpF@?n?*~>E>Q!%0 zCnGMMrRlz~Nsi`VYeFK_NVvSOz%LU+JNF@X)4GCWqajvmT(CCvA0e@tg|(0@4VQE4 z<`ueiH>5rz+Y~itRmri6I9C7zD>p+_3WvV+kU?aL*5l2BM5LNgdvKI8#q-^v&!fgc zQI&V6`O5SifroZf5#ktLLq3J5s)<^h{H8>_i%6<{42x*l@tFzPJaplj94!~&k5Ug6 zzp+_#{}E02F0NkjHghveP+>75G7-!^U-|gq$ADp^@>xNziAoH+;>4X?LXyzJ#}5b+ zyBtXbebvDeh_6T^zk=c+MNV<5)Kf&^U?z=%8Zbo`ukTd2{HppjI!@Q4;E`d{T01}d zUoVjxA^)@M{oVWUp^;&Jju(mx(4Q+qnZ5ql#re~hwW{USQVq3zTs_;r77BGyX~?yx z)nP{pkD?QFH5z?>EVvFQ$gcoM=4b)+dSK+mfrT+l;rw+UpmD(~`z7i5dPes=F+3Ql z^sZ(9%jZJql5kY6ipStPF-k7k(1r_@XviEn8mj`FWOEv%x8p80zf~{llw7GxbpT9> zRe&-htyUEBOJ7@FC?PLPJ~=|rAzYo|QBQ6+QQb7X)iUd={u$JP%8Cmt3O_{g!#W6_ z{m^n1jOTwBG)x*T^{^e|Wz13K9j=Zl66mQoHPqt6c#Y|CN9>kp#rl?nX?TS!{Gub1 zij;DzLQ!8gRC;AFqBV??R&R`*E{oqe;nT?1utUhR!}&rV>T0ykAb|@TE(6QXT34p$ zW{|FJe6JPERlz~Gh=Di!150w|aAbluSumX@N1o%0vnshJ4W>oU#WHib z_Z!Fm_QOi|zcPe>J0kZ1-!4#%GOF_QNan58bCnn$MXhppR7fxruo|$dOYs0+keqMjYg&S4?^^|ai-pXFzX8ZA=c*z%bgI^CJ=B zN)AdP{?_+_s7{;$hC|t2T_mnF)dML>*tO}W8DmfH*xCG%lSr9#@i_PoZ~6?(5OVHP zW=UH7pY7`tWH@Mv#=8WmMdoY|WMfVir3`6G*v6LY@7>T~hciPgR$Eu$z= zci4&=7{*79lO5j}dGMp!z!Zm%kX>K#bmqR%`(y)b3UVTH82qBm#+A?{qV2n%${-g?)4Q*vYx1qj=F!^sK1w7 zqG{*1OV_$CO|+dTFu_v6>f3~A!d^j$LP91DPDa90rF^DNnt_EBba~I5gvs>f5U(|< z*HoV@#kTie@;`0dz2($`gR_wBM;I-ZmY!a!p)B!NChSyO^yp=UGQBi#1Gd_}i9J0%p|jZYK#GWqboH**lO=0w>*s^ZA?wnrVmHnk0K<4*j`f57LX5gmtap{3 z4%jx_d9qxtuN}5}8 zZbvwNx|qA2BCc2Qtb4PFtZb<*`Wnzcad$H)a#1HTsRYcfrM#-HTG(|ylsCRL9nGV} zDlk8|S9i5F$81yrjH5YYDQj%q8avgncXySH?Gk~UB>(*}P3Q;Q@&3Kv1t;UtDKT?n zWs?&=^rjdv)&i z_Ep$aY#A(*ckMh-i4iCh>cY{-W5I1zf|9KDbzCNu5VU`_ea`=l(h|+fGIK#H3qFz| zLrx6;I(U8-K3*_=iMy4ZFqoDUXY~KVSKkB`7FAcDRWlZq&u+9hC++J>)bz<<2`q)8 z@Xec`)yjF-1w}EnH>6@^RLyzP$1lY))FDnS-G`8=?~_6_2BqfC`;B0~fR5hFrJ$|@ zgM8qx%vSfYAWea)e`Q5SwgD&r?tHrSXjZ9PA%Ks}%FEl(|N#xiiTiRV?L;KRo2TJ=9w3w>X7_{p+n+9-Y+(yfwLDgiEFTPT!gUL>aKo09Sf~9!bSx zE@E(xfq&2CbI)|{GsHVG7aJ4v=kz^MIjA#RD`2XIxf4L3?ZHGm{k#CAmCyiKZTJ)v zypIO){=!&lZl`sC4PsyazIX36nse=!y=tkTdyL@QmEe2>=SsKz%bYz}1rgv&IWLwm zk0!EshxQSV0U$5A~bK3r!y)Xh#Efcn9Ib4oG@;=Yort_T+ zmn1naC+1B@VPOydpck)ziQR`nU67A&?0i-OadLfKzvgwiP}=8_H3#(1J&&d`UV-HO zy_~zMs;X>Wc4^h`XNv_IRF{`WtNgF?m&rdb-WRlcKO{BDFU@CM zgtLO~S9p)y?v|LsvMDzI$g7jB5ljnwTIE;^3pj~Fb3RQEjS;osr>eUOu5+!gsKmWF z@wOjB(}|Bp%6o<%O)2vC9!)X7*w=BTOAFAD+v#e~_}V2l?%i=pmf}A^gQh6fIR73w z9KKYyAKG%AdGYVvL(ws?opK%B>zb$&yqAtEHLhRVlMVG|j?zTSXJi9`NZR#gPbr7d zg5nWf*H;b*dVhH_{g&Su#Gm_Oj=d;SQL>#xprCRFrT~hNn#}DdjVqeP%D6smQ^Wu33_^7>$0eYv5)sssf6)dv0Fk zmj{G* z!RBMuX-sN;p>Oz7u{P^{>TPDao4wBK-=3_RrrDzEYUb*C%=b}W#ng{-ov%ejP1R5S zRqo?2>Pe}0xDni>Cfp|*P8%n`jqrZODSuFrsZeND)Je8wPmZu5OxAlMnhM#=Rxk2= zs!Oe=E88p7=W~n7dETKcE4FWWFk1r*esksgZYMZ`3}qb;dl{bESxf0RVJKIPO&t|( zr_zj<+eB|3H`joz*V8*oDi5-Un_eS2G3=6?h#z8~yEd3TZ0)E=__HW_wQ z`7%4u{v+rClq*$kDb+h0thXi)7&tvD*s1IzzlQFw0DyUAcIS2s?|lyLtRO%k_;?n+ z4&vGGbb6mxXnSwYK924%LF~*03Aq`*(rd5de)cUZuA7N=mYAW z9gs5L<3Yal&3oj(2CgO*|BY_QwZ)&ev%niljkkd>PoCz%!HdOmIeYQqgqEOJfQ*0s zS?>1s`tkuKX}+uqtAFDWtpFD+FDH8mD3Geaw>OS}Qe|G(+sZ0JKLvbub8|V!bAt!! znD**gp8&Xo)ur8C)4{<(HTkBxS1nyU8uVzub_xKx^x(#_&Q>whZ>O>!C7=lSoEZNh zU^qU&fL0CVyegd(^g2-<1#0!;Xo{B+gCP^|3bbcIhP=~P=f;y<;MH^C^rNddXy@i`A=heY<*E(*ej_|-+DCf53#PVd+-dY z6uQjx$D$&5>YM=1A>m^p&%lfKMj~gQ1NvuBzjMwV%ox zhn=T^nt5c~E#F6AIvP4B6ww1-tZzZ*D;C0VG6uWI7wrW$G8tcaq z(L${fk_8q6`OR4l9T-8+(Nzt(C1^RB2z5f-%2P0|y?UsNMT|{*OuJi1bN$|+e)jf_ zJfVJ*y`y9NVcMrFSFcldVg4SA8y5OGyZX*VYxQ}~vgo00%$#hLus(n}ZYX?}`j4Fl z=;vQ*|C%|Vb7wL$gL}btc~Oh?pQOQ2@0f9SIWVzqm8XbdX14}*@bpN8u!ieV> zIee%%-XG(Wp*TL5-!Y)E>?F)ODaVJoIN+{hH`2!tKC6(7h4MJbT*SQ$N#$7==dOss zShm}4_-!{u#r99fe4|N8jy9tBa3xFjL#32|JFm3A$c@?gN>{FgIVG}{b~9wSE9MvYMUXr^BL zHJ?_#!8S|WglzjztQ%I(lsPnE;m@}BOw@vQ6~no|8fzPufwE9UnbRC>pK28a1Al#9 z0q4ax2JQ-D>QZD`*rVRARr_VhECJ|qM|SeWImc1k6mA-uG`i)5M~!RPR3#J-H)0x6 zOY&2jk8SGQ{j{f33}nJ@SfVebi)926e${+Cwx9m|CZ8OQbITZN&(;WuPdl+l2r+tb z^zmeUWJIaY3&X;fOHmE=*{kPq}Z1*4d$#DnGP`C+}0g=|bsRwJ$xK$IOAnWzd( zJAn?af_iY=-G^bNAY6d>G5C^*2(4Mmj{8Z>82(o_q&mKlsc>ZDCj6qKRz$rL1_uc< z<{vRTP1}0J%=jBil^c_vF0Fn}s%)XiZBwJlak3SXT#M!LgG^|MM!fUO0J^jDOl>+tdD8QS~`PcR|l-$Eax76?0L zL-VWHEe7AqDZgbCgoJ;1j@89YQx`yBMD0GFTHv=#pg}xrZxN!+LofHq8BbsktdiaF z6;PQBPjG+upN%P<tvu_#Nf1vov{%bSa{wwqZdiVs_=efhM&z zT$smDU46dyyh~>mM$xqQ$MJrNHuRG&SLl-q~6~ zDm()^zaymz6>bKP$rH`2`=`+g5~7Dy`P+*kCuq(_!jBso}@vY1u~# zscKJTrH+)9{q5mlPW0zj#uKC-VO)k3a)coxgOJa>O@P}8`B(HwfCG+M(dU}s8YM++ zjM;R2m^fJx$Kd>Pp79NcC3BJ3Y)!_<#s*@&d`zukW!91`8xxbmTGvAr`+UX6|Y+3W4*;#F8E6KDB931y#ZE@+({i zkS@F~tA(OpaG6tKuxm3->iv(8NEiDrr1H;t$1|}JCkbsu`7U^}qlNvcoW#>$%}l?` zx%%Do6s%}br&0V5Rg)3Bs?~L~G@P)-v_01k3k1jHJICfE*_6pr6=VqPA1$@w0}`Z* z#2}@Z1szanb-%G54;h0C0~eC?7J0tvs_yLh8ZdUZsB_ZcCofDELXDc4WJ>is>s&p$ zvG9lB9tev+8g>rUnATY)HrKHtfuP3fQ?cn5j?_GL8^ZOwR;Y_`lZ_M~*F&B-7bRGG$1dz{@RFEj0zT_6LII z=2!afJK8724a3lPm(7g+Pl(MS`u{cI=A(hdLX`WG9nuHaqN-fOgQL7I4Pq-znI!_c zq(Kv1cw3CL$H=dFYVne7Ss~Hi1-6Y(1tA1G^^lM1BEEc(wDMW8sbFG8t~)(-MfhPA zJT?pe`)#hxVf{77Q7@C@kl(gI7#bn^%b=-fh72XRh@zfJuj(UV8+Nj`*Em^QNjP^B zZ)nVbR%(Hn(&Q<-c4Ux>9d(Zm8B~0U+EeHM$J8|d*VV1>dwby$0iw7-~%{)JcS18d2 z^OHL_1zkPO_3wVLLbzw^bm@W1|M(r+KhY-ZVD@2)HY#|TqI^)c3*j5Mtn2*Tuq^52 z(6%aacB|D7O~Tf%Y#a%(*&qpl{XsQ22MYZWZ$Q8Bc%Vr+v`B96u}0r#HygGrCODA& zd;J49>i_prUH`wA%Kz)*)AKWApa9Fgq?A;gD2ZBWxuW;Og>F!A@bO&7&6ET{Mz{Kf zwt;)@0v-&9`?1rgHm6?Lysi0dh&*ctAndaompyL6dk+rNceJ`a0ogQ#^SY<=surHx z0bvvl2aq2V<3BvwHQ6vls^f#Jt$QJ$b#_GvC^16t~ZjEsB zsL1XGiug{0+NI0tx%pKH$!~>8ZY|>9C+#YNZBP$vQ7CVOQssl$yf(pbOe#d;9J z@1z^ySmJ&qf53_Po!(n$)~Z$Ik*@8{5o&kF*TR-UF|H1V!@ zX&gAT;I23qpL1*~8?)Ow{4F;DU5SY(|8L~bt$kHqFR+OWK0s<3^QkmRMZcpvcXWKxT z;S=kgAg7X4zcjoZ%{vx~Os;f%-gd8L)q2^V<~QXJ|8)?6t2eqm0maQm6xUhtva{n0 z08CeJY;V51*z9RNbF5V7Ikidg9t!ItQZvtV*@Dz^-AxR8)&)usM|TeI*FQ)1?>ZNJ zf?}mV0Fg#OSXo9rh6=r2{8;;!P0pFxF8AY3JZfW$>Wd&ePcQJ8ky}>|4^5Orr~r3! zcRvKgF$xFzQ@I>#9>IQBS)eTyrlV^SnifzLPBUmfs(quHeHv^lRG#9qFhfoie3s=2 zvt;^HYD`*ksF&M7;8;LIzs>83ct1ulWRft_{kcEMu~O8Mwovo~0#thCA_>d`p?W}I z>ApxI$l=FcZUo1kZ}H0+qkhz%@Umi0rzqnI0{uLyZ`WAE=b_n7grE7NGcDgt+LYw- z7`7ruHw$cB*GNR_C8ENFCB<_FpjUP4*1`BVJHG3hq9umr85@m^yVAA1?(<;yiGu3A zEL_uBAcq&n)7NM2B#UjQW()|@o30a-XnLBcuMMh406~5E17hKl<>%K4eg1s#(6Y zY}FF^`uaLMJu5IcnJ1F^Lt~f&0C1{fVqg?6Z@;qydIKg&y`CGr(>X3ITyVnx_J zpKgv0-$}K*qzTbR*$LnF9-1V4~w$2lJ^v%!SOv}fJc=n zZs)s#3GkSdJ2g7e2C!?2vZWdII{AfW)g`#~egqag(}F$U@8P?~C?6PXKDY!}qLw5o zKxK?|9vsZ#Ry!Bu%hw}ER*-!yT0B^JNehLG8Cu9z z;Ob+Lp{CF$yM*}|TME@Op{=RxQx{(8K#j5DuSp+qQJt z?(5s*xc$jO_3V`g$fa>#>@@n;i;n>2u|!=PsZyN#YLNI{`ikYabp90phYg~4 zJoG6oeU4zbEui--DOeK0_e=mDb-VTWK(KsQKB=ivfZw^bP?gE8Af1-=v+!}f{`ahT5#WNjK-$2{YG&;uv=ruwHJ^kC^SLX@(A0JfLasibu8-!&`|U~= zK0hr#+pu=yDyN5EfzVp`gyWRS}!2_wS3+@Kxu7`e8Ph4 z=IOCUxHs;U{mOaXNe+ z&=}F_e(e1Vs{>hBz{U=)Q2ydpdE`Fh?0A&;qMghW_ry;DFSFU=iF0zZz2P5bHC>a# zBa-&(RWirp#r)Bn#~xD_BT{_P9d_kz4Kju+6;de3OzR2|J!NcD;k_>Wd;Qq1wxq#D z=@i;k9d`y1(T2Z@xlc>7A*x`iDwy|<0@=~`niG(RoOG*FF1W*oVR~g88bExkYkDK{ zWpX%KEIBd}0}r!nS3){zqhsyyndq;p=##Dp!LsfgMQ({y5Zx3qoO zyzE}{9GDesUq6Ci;Np@h-W{$1Lbl9h^@|oTaBvlCmB5CkPod<(xWn$a#0EGBGa4<4 zOLiOwz&r&GonA|0^}hYS&010C=PlFa>baM*q7zMJdHo&lpB`Qt04Y7|34r*$M{)#% z&F)|?n#Mh&lC`~DZ*TBlCh={74>pUlsi^t9cHf?yZq;0(*Jejqsv-W7m~j?4Ug`(C zETJeYENppMIaBpf9$ZiOpBcB}xNF1@cDbD)Cm$a~j?-sK2eU5Z#AeQzTQ_*tv#o zP|UKSd8&#Eo=eDA%dGDL!9(>VgHz* z+@12@e^dEBmS;SUL1tB9IpzRG$0n`2 z`bBHr5H0~XEyg` zit8yQ?#N15``y3>ZzOZ&@l{$tmvxpOwEDz+J4LIb$aY!^x>InZ&PBWgLl$f0aK=s$ zMQgdLHr@g*quyvVUAM>QF=v&UMQq=79uRk;Tl3#S`S#%#<3*hGq^EE_=eQPY^O+%- z_Eg8h2DT7K{7f%ZCH#6>R-3%=p~7`YdRg28cAgub~MpOKs| zKzHr7E-FklBrd^m{pabB^r36<>GqVM%D25g-e?*B)I+;q4J%C4&~IiT?s3VK-;Ara zmB?VW=bYJFFd4K&3aG8*Xm42Jzr5Wiwrhd^C8wLGNhH(NYq;+W#=@4rD0|;3$DI2I zK4(wNR^0*YwXzZ_aZ10Oi6c`Vf%dD><8Rzj6;dc(uTb)(-J3R=k5D?mk@s}81jNde zQhVR|2T=TG1_l8-CNJ3Eh@YPiT6EFZUtTQ&J1>3VJ+jXRO9B0_jtWt2%1U4o2uR;U z)}WX{tmu$zlKwt&tf0dT0IS zW~(^saaWsFjv)JbGX5Ij4-Vg;0WeNGyfr<=BA$TUK=YExW&qc@N`GJp8*}!MbC(DK zBgbriEaQ02GVyAl`N<9#x0a1x#t|sCdo_970(5~~0Ut959-W=icb2N2H}TMceb%!E zbfeLBy-q-h)XYaz;+Z8?=wq;Ar}@9=!73IQX{jr#bK5Umg|7MV4buiAm@T+GUq6#; z|7s995o(>-!EjZ-1n)%maWE&goX{pl8P})>@!qg4~cq|k&uLY zr8Am?^J67U9*(nr&h7v=9Oh$$rc1}HpSNlSx?d*(&&-RH_NUn8%2*})4TF-61R{?w z8_+!-NL#kVqKVVHEZ|a1U@3J3%%Cj-CY6C&X+hJK-CLjGW13Hm6to*4;MSWN-7F=; z)d=;e;kvcgCf#1V zHG;;!uDcQ*(h^^EtSzdYTA#9lUo;9Na4vx1m%sTk>PRXzm#^P|W+cbL^=|010fUg+ zdTNVyUKVS-alrp+)x6>DhMUH4^TvdJkP(z@|apbzd7)8hx)y+Psm{riI`(rAI+aqt8?Y z9Hces$pp8*aXgAuwGAQV)caJBUbD1WDzK?eB5BHhhUNjY-<5~C74mGDbR75eTE;n5#{XmPxiDeYc2 zzPKufkQkM=K2FAiI4bQaD%i%#K}+@!hL5rXTBZ^mfXhdfQ{TqQ<($arhhDvdjF*EG z?vc8f+@@OiHgeEpGFjvFLEV<_UrxX%Pne8Hl4>!Vz7d=IL&CfjXi4hK5_^*yyCnkD zhIW`9Zz|F1?^8UiP7Z{iK--#7v~Qq|*g+!MGCtwx5j*lPuffZ(o~tH}!t~>qIsKNw z8k5|2i&T@thklv53N<0kE<+k#I`mYs-!wUmr)>P_RBHUG!_MIR69uBP%IJjxSNHf_ zp^1@sgvc{3B2F}XPg1WLruhkbwuOShCz`Uw$Olp8p@lM0ZHIS*WMC|vbGMn)ncT(= z*`iTX2FjkQuecU>$Czw~+>>K6)b9`&8e zlLy*?Pz9hRS&>?&QdE@EF-uYo?p^0gY5ywKY?jJ^#_^FyM~VN_H)hs#aL~7gvds6& zGyf0tSU?>kusVmoo!5pQ-ODL8S!>CN_%2KcYLdd<`oLQ2u>5znZRFz|26II>WhV`9;)TiV9YuucDHf8)l<&l%nAUi{VkNvRSdYXddW6 zWsLJJz|kegS|!=-ZPyI_i1pVIio*J~Ygs%*MOeNJ&GRyW>o0(@y6?Bc?RK-fXDXZO zC&odE&yh$QAFE+?5XoJqrLcBwA{i#SNHSm`M@f2 z4}Mr|_;^j-4~9_l46L$!hqUJ+M8f#&)5~2-nvpo3c@EQh(x~w?%a+UEKNcIXmmR+i z4RNq9wpt9QO3tIWzh_p!moD-DH<#X9Oc!c9syd&8wEV=f%aQK{=#a~@1~C!!{qqxZ zQ>4;mwM$S8)IHFqxAo@vq0sFwQKOpMff-sOLe}WB`|>DC^N>Wa z;UFcf`jkMI_#1+v(Lvg4s}wrcq&yHkL>p?Ag&hpU=+zZ?a;39npi}LTlgxB*sH%dg z88vJbP;jd38_4Ka(GUZmkJT4>jF<HOelN*U~-1*#&#RM^*)FBV`k(@j~u^|s!PE-*5Z95|Aky90v1A!%lDK2 zPkbjW|8H983?od=(R8gdE&0`o&D7VpMA7QeWDdm;4bZlV(c1fK`i z7;{swKed2rQC~4q2{%p#vwA2`FoABDL}kON*-S5v=jy6T7oL%tWUSg;jE$gEQ@yM? z9+wHW81_LI1y!=3CRUkt=Dj}ZADU?c9DKg6?pW}mRUu#QKm}+&i3wOZwuzlb)W{t7 zyn~sKz3K^3zYni{X?5i4Km-VH_}DmEK0z}j);DqH#;wD*SH&Vq@B|2ey6G(tSs_WN z-V~I~6%-pKgv$;zYDG}R4(?BG?{7{eVB)jm1oVxlH7lB)Xf^1xH{ zpP#P+gzTlFq}m%qEKeZ#$HOS>DL*jbBKQMErFxdwo~gq0u|KiCQQg??H+Ry4ScFz* z{FRy2)(R3)&tsB54|>mTAivBZ@P3svk$_!{U~oIZMM>3b$C>pXAnla1P?iQ2&zhtD zy0pMjry00^j_77ob+2Ed`L(eKI-(G1PbD3W1%(A^%H31~N(s^mw34ujL>@ghE`Mfd zX)LB8eN;9Xy}WuFxz(gpJbu6t`j|SL-;b0Jls6tzr6zKg4bao_Bd=ILH5sp68i>RS zrj2SXPf8OEgAI^yZ3ML8&4BF_yDUisl0d*pd!&vc zDp3Z^W(@n$N-7nlJPs#O`e$<9(I(Jf08ebpLqpnYeV_cqLV~E}7{?bo4a)B7%{&m% zM9e1VHMb^qIPXnm#A|o`fon@J(TFb>Pa8JWb%0^v2|qgYZRfwK_~76Hg=WM?E?)md zsS+#8dOI2M-XI*1xa=M-qE|%wNP}#9_9RE6OjP zB(2pX1T2ZZ1I+!0Ju-BPP?^YptZM4x+9H)+%<6vzHnuxIw6+(HqbfS&h2dp)jf(;Ucejb5#iwnM^y(BAZ{G>?BVb>gWX;Q_9X4my=8Uq(ed)~;j9 zdfBSh^(;_Eeac8V4#C;AYm)g}&!(#bhRO*{jL0yn)tV3bpLR~bk~kmrJHE_~L;i9| z%AK>26Z-E^%4PJgde!>{mPv1uO_50bM86#PRs&6AX^_-M8)I?zjUeH!A^u-1z)=Y& zy~cKH$l>8Sy@Qtc(~d4NHFK^;%+sXMgKqHi)48?p`qHY~OR^W(I_IRS>`^(_MiiPs zJ{^58_ug}sh947j#_^%RO8z%yJ-Rj`OG!+^{OPGVWvw9mALZPYoRmjwBAwd{&2@#9 zxNPdgYhPfdP1!l-o4(SKVL^j3Q8F1Blg)ZjLPogUF79t)SN_bXaKyF73VLL2oyvLM z8cbQNV3lS&+&l=nislr--XZN`&~MB`N1q@k*Uj;-9L*rx0$YmtK1*jbwb8<94PF|` zVd3ei68m}wEtg94BRW3qliRb*QdEQ8#Jay9i`ef|G7MYYCVLvSz|YWg1nFR>-$eY3 zMwJ4Z-TpJ2GU^JEc<~xkC37st)MX3k*>lbz_Q8Y6MP`bzxWL+JNN0>{%0N{aju*GoYmb-&=hqkkFncd<{GQ`@Rx4=7L9a9&1gh)Tsf zAzdo4P)m}cu(wrUrI@ z%uHTlJmRz=kRt>^`26oF24T-r~ zmKJZ-G3#ql>!t?AxjeKX1ZY2gsH)h4V9SE%R;IvpZF3Yka+M!Gcy#^Z2nuOU6BN}y zSd5CB)8+CtdLX=JwA%6&NlG*DrWk2jzF0rosc)j1E~S#*$*qn|fhMj$cgVVg<%`hZ zNP6Y!2N|J1Q8*2;AL6%Bq6OK%wJt~RO8VN>J8839Y}BRZx9%E3G)-(0l*X`8eoZGt z<9BCvb6Uw4aaF^<1y5ND!Pn3|2+Q%j9^EZA`{NaI=SS~%N1vO#PuSjC&4RT7^;y=x zWeAn0cv~@4Rx4OcYz0+IBD5KSO>PFQT{>PKDnr9>SU#i4?;B3Puq<68W*7RYaP&=X zMn-(Wzi}2Jp#N{<<94Wv?%~NAFwA4;FkW+c?#Q(ClDQB+xa$_BFV5^|p?g-7t~I?5 z9g~u49&>YW)nx$LSB6V-YR30@VGLo$ShXWCLz4Hh8^S3rzoi_Px4+2=TdzE11*9{4HH+vh&*L!%EI@6#fY4}N(p0eXLL6f&dAwvr_6JrVz*4eP zws#hn6mzMKjL0%TssCuUi-{q`Nt4JvXNDEqmz;;5V%rh z4vuvsE{9nlx_oM~yl0d^sSR zEO^vHrynpo-+;uVv|{p0m=8aL$_qCQu@)#jzxE#wwI>X9S{$@giGuPe8upN+%`F-@ z(pn1?HZ^%vYF?dKjUL_W@zP89qY-)2=+M=AULAAjA+ErrVFeMWURlYgRC%aqz*M}5 zS+iTCuuiasEewH@q#{Kc*}1>80v(79@xY`q_c2bF;@_-i0^|Mc{`$(n0seMtEPO+` zuQTEyaJkdUv9Nw9P447MXzed&=gq@d;w~gAz89H4DMon6H{u~z8%v;gM7i;$adVz2 z<|NzTx&nKnkq5z)hzlo#-@DV}r5`fIME9n%(0vKIqbaYN08BVHO|*ORtINYT^KFER z0HY}-v6wWCpaR+$#4#F-M^m$=_Kt6)a;;45?!8RZDX5wRJ$38h2a=p;Tz%C-w*3_#7Hij{;|8apw8x0eW|wErw|r`XSs)yD#@kv4F8pE&(qZlO2?J={m#^2`<2HXSiE3HtPw&(2BE zE@AqRzo}>E3XAT?7f5kf8ESQjgvjaPjIZ$ZJH<#Dc!Vn-35$@IHwd8HxGGHYwU{(G zLvV$h+I~cT&JxM^QVXW1_JFC4SF;G zjk^NKeytfS6_}sNIk%XCt~T6xCre@w~9mXyLk@!FspW} zaE5ip1qi{KaDL%Z>wQNPK)iP8-!|IOgpBTq2%uJp(Z;4um86e{ZO*0+N>f)McMYry z6jcBD49|uocrQFz@)%hp;(9W19^8)S&@Uxrx$)-Mfv-pSGX@%UymLlCLQfGbP>xnq zt_#5dHoGvcco;cmsohU2G+;C+^M}tg?sp@{Cb7F4zH*W}jU)}$PeXziEf$W%D?5M$PHd52x8RVca$0#N>D~ig%f(W5yWTR`LnXsz$(>`9~Nqz zB`U<1Pj@OE4BB)q9(B&!XhH$l}Ov7|;VNBAhScQi|xjCP9Drm9UEyD3vSh%PUid&$dI z4vt+L6SHRm3pCXjbr&rSnt;b6*gYVo1?326KpG4rX=d!fOs-!?}a-psD*x~y03 z?f&?KyV`Ny8CQStRQ-9O4}G(jTHV=G*}tTuY?a?wlw{+fvhw}@qIDnCB-@m|}&mjk{O8i{P0I;yP;PT7Y+^*ffs5*3EL z$3I>W!Gy=Y0-ry^G3iyJ^?l4oLWsy|(JO9pB^KlOL4n$-^B&rOp zGJ3HC49T=2ZZ{h?slDiE(W)3!096y?sM>QecnVNQ-9KOQMx_oyjH*h0%%m zb3%h4-eCH3UsPeS1-o2H*s?;@{Bd`DhOueQks~EWfM~u#eT^a_gkIALO8m8nJDjDo z{vu0~r)2+8VdupfMXmP}8QpS5`6^?jZiGRtP;UPXpcZQ+wtc$i#-joQ=+IVXHZ5sF zr0ZJ2js0i_UcFzcD#-rV%=}0pn5fwn|0usaU3o?jJR*6Z7C+=o|hE zpDQPhS=6;5wAS$;yNe6R5 z#EtA|O7LBoN5YQA)%Y&M;enMxoDqmqCs1{cc~zwiVK*qoilDNTk_!*kT$oC(?2~Ut zW^bXH(S52FN`Uia0v#TPohm8KubR0k-ADiz_g|#Wq=cO}&u~;L7zgj+<@1Y4N0tHuD3erGdL4E-O)-a7sUuNRAQ;IX-zVa`1Tc#~ zZf@m7SSi)Bq63Gc{L<*DcEIPKU(KW|3*k!C`2&1YKSMnfz8 zin)jCZ#YIB_)Dq9+g13+jcxip zehtRYt2%TE==%0VO=&5V+HvEdMC5PVXaBLPS|rQ}&IfCj*$%UFIf2tSBS`&0mPM;W z@1z?IUcFZ|a(Z|w*uuTAM=vW{B=eI5E)i+m1Ma|9pb$j<@%L^XBgUafQ9J`zAXTKu z@gZYdVnJEHAmPEWaIAo|qySy;6__k5{_o#>BXHBTHWhucE}vRtILME7%4j}FOj4Y< z;x;_O94$~Ya7-?70#x+ze9Ff^2oN7*90MoLtY$I^WQ)*)*{bfY)iVVWHR3ZOcItIN zi>MY$a8*(be=2m>#i;g+_fg*)&yP(PES=#kyt(UO2jhDd(0cxxGZJW2{!g>mCK6yp zN>dob5dnZMF%l$}``O&qcGXkB!R_*4iNC46{VOmP9lo^&46raTF-ugR0Ug>ffHpZ_ zo?+XG|PVRn8eu}(zsRIA}R408oC;m z6?%9qvt!s&p$XoDO`dU!b4l7IE(==EghPR)O76)@sHUU@9#Vc8B1tu@ZH5As30@0n zZjIo)@}OpGp)5BeKDvTvU|Wq!9Lb69FzD~$fb*k;G&YaMH)GGYazU`a0|Ze%0k#D^%Go;>?r9TImO0&mp7 zR+>9^_X_?E0T7j@|BcZBSO7u=2?EsY3>zPxT$S}KPnNb5aLSXQ2G{rp%}P7VT6TVZ zzCV)6^!@u!Pq()@b!$T%oou6*aQgPahlhuwLv^dBKmdT&+-8yAE^Ar7e6gS(ZF{vd z1fUNAl~{0iyr0VwuAa3^1Nh!Q0J+(pneF#$?oF5d*y@xOvAioYz!q@2IsOp~k;HpBx=Vd!Fd8IL>Q2&c7Zhcl>@=zIA&7pwJ@2x4ZST zcF3K8QJSjl8o+Gia5#`zt@nQD!LL9ry*ppmuDt^&!>E1=j+SHipxT`g)NVbS_0Vvz zfR{?sIjJUdM;zF*48<1N z=dC7<^3(1zVMPxBkypP-l)QaBE;MggFi%fC!`FFj z>+mmY!Dd-|&5bx;2L43evOnluI=({j zS^i`NbdHMCo4e}acVV)(z_>$UNNRT4KA0V=;2Pb0Ioj80am1fH`*d(PIY+;I3f6&a zG$l+E);Ga}cyq;_JsAtKq@+Pv;f9kGA2YOd2QC|hky=nt&s@?97Mj>`-^w4-q)Vxl z$f_vpw!4T8k(Y#;;6)FF*dnl5Vo+*2b)Q9)5ksooVr-{8eXE;=CUK5ZoJMTn&y%|7 zZckTgHL=q|U#EHm)_lXH1*QBYQxi&!0#?ape;+3POz*5Gg7IppZYu9*pCyVmVr{|vM?mxJkD|VmWC1n39 z$vbyEub!;7G!`tm-R^#w+~<9Bjl$(>Xg-(EdO~4a_pl$WXOmMedj;$(NdP#m#OTty zI%F##tyfmWdl@Qib6nmyr}>=qdYI+18HmoR_%`O;UR%Nb@nVoT+UDuzaCZ9ir}w{z z-oxkfj;v4Ma0)XC&}yeh`Af3iCku@I{Ug2)>DKL-Evs6Daf$Y%L*k=HmHA2s1fwJc zIl3XU80ai3zjx>E)_;s6DYK4Q3*VSJZ_O@HjFgwp%fu`}Z0n;QH$+}CrnG!X6z1EZ{8_MOVBk|9T|%z%l`e)c~IoUAv<5&kJEe2W|HZWpK^;+GfBz_4ijRFE zdf1C?*q-nw^0?oa{_XSR^!~B-*uD=g;ULOp_wQ|1W*@wWZ1jF}sIM@v>6h+1lUC*| zEM|$KFuPH?WP78##8$-Iv02%O!JN|UFiXD& zT=gYGW@QnyrI6^>VqO9kh)eg9s671izAHp|MbVY7mPRDSfwSl3J7|AAp#B?kl~Mop zbP5sq&9(u%SR6Qe!1cx!Do|k5vwp$ElPH#;Rstx*-58L>*eBtA^Pi+i4au(`Rm#F94;m3 z#k*cHcIg{{F&YINT0vaip4Z2L9jI1HJG%}rs~@ca#hji1AKBqRXmk*l_2;#L3QfQl;-&KKsqzP} zx7Y2>yMw0F`PypI)6vp>>pl;lstQF|_JbM`AUkWBde-LWN0L!nzTY8kzy6(XbM~S^ z%B`uOOAX-39a1zM&15-ktBNTdfmoGaenubc(3WQ zTecvbgBg?p-l@GH)d#ryQUWla)eo;A?4HGaJ5S3;HffAbQbmi(5>9sP)$Z_HDW`eV zMKY{?7EX{E8N$(;CLY)xaD1ttB}R5A8#q|KEHjc;P7x;psXkaX{0txgve%RfWuel# zY$tI3nwT7=8v?K=1FR)gxIDAKyC@hTJxoVisQQ?d7zjmZYE<%<-{V7>rsE5u|4jOU z@0&}1z2PfNk09lkzyU~`^dGqR7jt4>Jg)~`Ad6F$_C65A&+X{w*lWfv0eg4nRb^Z| zc$b1+Xme+~RE4L1b@15{*iAnbiNevf?edVjJaa!I#EJx>$RPkJS1GY{ewmi$9TiAr zcK~k8$d)9eJTDFf3Ba3Py=uoTh0yJR=-Rrg!Ycr23Na_PfU$_bUxNN-U1&6)d+H5X z_D1LAgF&%Ebz^3N;#k{YRP#AKlUE7Jzlks_dmE}f)aY8sB; z?CU4v??lD(+rC{H2G8(%+E@DNwHs3^`-Ua4{9$j0!eM4VS@@wYzUA3eWzEEZHKA~x z@)b>Qe89EOiLaFz)P)c31gJXAaxqk!PJ#@dRiRnfI=u3=7(jEXFiVtq?8esv^Qzzn z4B5^I4ssw;`@rJ;X3aRYnS=0P@@lVd3$kS(+U!9zRs4o(_7yw92+>`dWhLNd`l_Gu z9>o>HWv?-b{rZBcT!X7J()imZY!3GO4-Wh0=cTplvNX=E$daMR%4yn7yoBkrES44D zO+NpP1PT9e1DGR`@?Qr;&MFb|0cKYB*49#b_&bGU`*KF(9uPAz_>!7rhCR3M9;*E- zSb$7Jb{%Nq^IRS@3ksk7hX~tU&;JGzwf;s?QGs!EQkKz@8AspM z&*CoJi?`bQ!s^)k$BeaWVFRNb&&zhzpJgqj?rw$d%&Re5c&CxeBhZD==n3-ncnqFmERa|wfE>-D!9yC}( zOpU#K>Pc7q9+wK_-eNVS>);SEm_UN(EgYw4(2Lyh)=LVr&d}e`JNU~#zF^CCN4g`* zeX&>F?fd|(;E>tZ++Nfe+}Is+Z+b8mq(%)~8^d%qCJ>hbm5~-YS9e7RBrLJV55?!O zCxRUEvD>8yDN)a>17g;qX}>vUQEA!3E8>9ELz)Of!f1nqx@q{_X)sjm?-Bp z*CO-qwmBsO5!)Zt&;9duF>SeYX-5&-$rnD}Tf0QSC&P|eLm}uv| zcqxw9&V!CMu|}L<%~QbB49nUMjWLtRZ5L^~Qc6~JN!Q->Q&QHQbW+@B;Xe2rTZ7+x zMqD9wISAjSH$<_U>OUxMk=Qn9fYV+t3qJ~hd;iCse$(_hh{{o6B(Y^A^3~iA=4vI{k zflasxouf3#-vSXvusr%R!NDhN2K_4a6FQN46DY1H~>gVOP9yd1szZ8=m;uC)FtM~s48o4Kc7>DFd zz~^f8qZC2p+(yarHoI}oZ8Qg>v;uw;>l2+gVPH}3k9avs!Ghs=CCVOu_rXL%15Qa@ zyQuCNlKumdt=r)c3$V*c&)#zBCt~q(Yr+O69jW?OYicpcXkvM^k!ZN(dvYehTq&kQU%XvOB#HxjPh?rAnU~3xNq^B86c9Vk&5N zS*d4W_)k>DIOVUwIC$hVAX3JZaSZlvo`x63w<&qOKxa@(oc>cC?Aq7o{Mze&SgVcn%EZ{zVh^7ZJSh& zSMdMKlEza<@IPvYy8gr1(PRiY&Vtn|wjK=l5f~2nyF4x$h?F2DTvIz-J_%IFNZ|HR7bv8@rXa!c4624BIS_e`JT zYli>tjxi2E%m43j{AX*ukZuLXz>BjKJ6LmgnF)NYiu%=?2qjRJ1vP`zw|e$`moe zi2Z}adw-)Y6@5#z1pWL4N0~^Wh=kIGOguFfs@);t>4N>X^n)SzJVY#Y5TkM=+!bayAkk-?JEShBWLvL-5T9fCLsztTGI78Vp!qNdX9?LOic>>Q5ck>V zpx7$-~)l9`fD4!l+%nD;W%2#Wj(@}NzhfYM{l<4 zX#wLAI6P#ye!MO4_*S+FxflcJ%h)b0Gle#&GLOdjn1c7}z;H!rUN(mU2WZ}$)9SfBBiK-3eQ0#<> zgxTN539ix;?D~zv`$7c83n+*n=6!$&F3u-%k%AOUzl(|bR2Ci6vpqOpNm%Mc{Gm*8 zN{)@=cd^fLNftG6SaEttWX717isc>|PoPVyzl+_7k^`;f4Gg*8!)6BBfg$x@D()u4D15k2pN#8)ts_N}?Ii!U86uYIViq)#YJfG*6=?rie z>JzJG;lE%Gdcdbj5u;n_X|xBpR0Z6x&FeV8thGj6Ho5jnqaik);YcSetq@%KlDsSq zqsZ|$Ku3C;Z$TPR1^wK~R_Wzs6_@#i;S?HXtnVxlWLGA051~fL;J1JhUD4x|BNLbn z9t1fPTaSBWuPZmlEikiK!u*Yt+C@dp4u`@Z_7GuBCLlXqcmWk>pRakk7h>irc(>RD zWGm_Ev6Rn&Jxcbc+=;9V6kH?{9NadImD~`{_OqP}g2! z_bth>>zy%?ea*1HVG12jH;@te10P9NGZiasxkO zU7h2_PWqY3*Gzx?n5XIY*H+14MXbm@od3B$UguWF1pF*d3hy2t_cH}(bTJ(M&2*#+ zZsKfv$TBuM13?2#$g7>aXuMp|^Kz>LBjh?1pzCf>_h0-gkByBslIgl^lI>@yh&`Vv zJ+>!x`tsMCAUiy3TR>QnWmxEUH=@sb=JD?u3m1PO$p|<9NG?nPy;wDTc*=W)7Jr*o zzfhld$9^V(_qKy?pWEjIN~?~V2_Q!@B!jd5Ra&0Hhg;+RKQubN1noQb&Lre8l)%vE+0C7$KNU8+c7dx3wGgT3j2 z#Dr$oA6%+PoqWII`~tw>YmBw$cN3cVolHFCLNU+F%aUk5RT4uE=_Fgut?lz_1b3*( znS%T8pzkM|Oh*RhH#a@lpsy{5vP0^2Z(T|kr-^opPv_N}5x>T{e%xC#_ynV@U znVI?B@r3Yt5Z@Ih$IAx&wz2yXH&TntX16Yp)q^) z;Bp!qH7cj&Iqn27UO%YNceCM@Rr^a>K8=0x@c5S2r_o9%x;tK2XvIC$bLSJ6{<@)m z+qM|Fh@o(F#0^8lf0Th*@32jyw(MywM7wH2E|bAB3|4O$A z2R1uWi~Q%yKy5w=ieoV+Hf~F62Ic5X@!a}pT1~=@FC`(OSxB)iY3|pdtkzTQf{*ZL zJ-@%K?cnriKjIJ_$28qSuDE5bCbyld3-QQ5qZr=ugjoM9S?pS+391be8$n3ykep8gttSZKjiWoj z0ENV8K(OyISj1JeD=_bhya8$*(9fCV5uLA8%7Lp| zK|5GFBr=J?)Ekm0q%AElv#`h(vjPrKZ{)Q8b2ah@Vi1(EDqJ zD38{kFM^WuwK#i`fBnS&_RHFbZ~DFt#Lmtf{@B0n?bb)nQqBtw4|75br@m*iFNK5cXj27wRkLKaR=BJ3ovKJ*i+z&CXO(_yz@%T+P3)m)LN3-vt7ZK{3vg4B`;Nbgt>#BBuA8>lR0p z)BSw%hTxldO|tT*^4j6)LS}yDnn(qe;TNjoreNih{z0rU;{GioCW80sEodzCft1LZ=)H$A zp6>nVIJ_(ha+oo*rJ}`oIB&%H3-w;CUlkPgQcRE3C9M0oA`xHs9nc&lP2{Vw!fzt= zevs^JXIu-Bh>dhwo4*zpg3qJNw=tM8B#H?S1tPa#NodiRx(+*_r;QyGW>tmZbJ6Ijdl~0lMmFfW{U{tpOi@#s76Ni?y@j0pUIP^ znXli%&rZ9nKVmmKd~J9-2}NvMu6Z_ov)Jr8B@ptO_U5CCTcidK*9*AFRmv7&C8Tgz zddn8+n-Ub*7|uP1wuYruix+f2RQWg^qvp}W4vBX!>+Rn=qAQwwILM7x_0i%@vNh>b z(}}KcNZos#R5pbSe23J5-J-lcWOVj-Cu+w;i-77)cak|=mFUKG5j^0)u?N%m*$$DBdrl zQxd=gpIgcME5v}xgL#6DGhJaFwQ?jUp30>U&pr|7m5hfTUcci(YQBe!UIi5*7{Evi z2hs8gaXw;m?utQSYq}UTf!YJhm}r|3SUdW%LG<@8T(XO*DDbhB=$Cl%9;oI{n|EF` zKc$Yz&0<*p9(m6erxYKA&|9OX#NDxL*d)S7#VJmD3$ECH@6RTbK!6%o#I!Xjwv~ROCzvfp%DzDX&ui+-O`4nc z=*wyCX-*Ooc@4a&<=jd7YTPd=^6aV{EngBxD`#w)^=ljLR}>A~B(1_%yRpMsm3<^+ z0jPzBmw7~h1!Y_)Z6C}iqBmcYzdjrie|#!O=nfg+bA}E-%%|McfDtGuoncD;$tjKo zUnv_=uwKX{rnl(yet;%SFLj|Ry!l4GG=)F05CC>Io?-Sr%KS)Y6 zi$(MFEWd-BQnlGiOdyB^e0S6^Lkdaoe0ys06)*e+|0ra;|1hohz>|*~U-Gt^x{z+y?i2?bB>#WyLi&RcVF}OoOt!k{;yv~%uJ_3^Ui>{s4xFBJJoFJo) zSkrsdU)yNK@j;jB=iB|_F|@roZnh2Y?Rc*PsX1qcFspc0ypGXkR+m?!5=_X13UCDY zq&F$X71TV31(B8D3gVpgMDJZrD7{4n*XTi}C6eB8V*<-hKO@J{7Pf=}50(SETru%q|9J(}Fq;=Wx!oi~I8;1@|t95UzGAOjVNN1T(49n8#X zcuqhw7ci!G>B*$P8E2F8={aZk*Ov}joI)VFH~{r5N8IpF4m;o=Z`nRQOzDoxEP?7~ z(x))lMn|zv+Ws5}O6YPeO^)afsL*P)pOY984jeO#amt}5q(_(gPfDg3zg&`~ zOJBvhjp^ZpnsOM!AM_j8;DF%Z$pD)~xv4loE#iY-E7YFCFpE{hRo#Kcw|8z6-Fy1z z{Rx2Qe}IhST9X7e|N4Md$Qp{_#~#RP6R`Y%;I1MsH9NpIpXg%0HcsZML@Nnj;iOG3O9KQ7Ih z-YHF_&_tXyGzHBU&5s!Vqi+p8Kbz{u&;#UfKWS3=A=MExL^lQ*d@SYGp8)h=eFp+; zN*SRM8VXNY*F!+@r(P)1QjExOGeeyxu7ivDB^w|2?Gn2zrp?EuXrAhy5w3_uEo`pN z*wqg0i28-!1m-wT?_oCxhXe-GI7FbYQXU1@i-KOq5jl9hT_*_A7ewQwwqUs#VpW(Cm)`9 z+%e)G(=r}0l0|-BDQYc5zTB%I3E^`9(Mhi*&#q}MzY{dD!MB}%V z+tx*xn`=V_?yIVa4rcP)vFj`TKkgK{h86YG$LNG?{zbSRjOl6O1f*k$iET74i8kEp z9#=TP=^}lgb3qydzLtcpH}dxAB$Y@rEGA(dsFy7%EX~Aojkk^2?;kmG(As(-nkc13 z;b8W8wHYZr76qy;_5)SED$-Ew4M}2nNX*GcyGnsxw(_ol7gHHIK%$cPOd;??fM}rI z;fBPxEsYdZ-&GB*2tXG-&9Z%L8mgo-U`@|; zNM0V)>pej^Up1vAU@~?_5tD%dGwjQBDK$DG>WG3aIa&fGywcm*fz!O{ME%2WO5@e< zLd{L}=;hybI&4B8H)nFPtThjuI-N969Xdv?R4OMOhEnTgxC9vq)0Q}zi<{Dwc}kKX z=@Q^=M|*4N`s6@k93zWOG5I9av=eE;ZZXO1r8!`dv?IdKAITk`3yqn{r?&L~Wf2>} z3FIKxcdx5vicINP6oguv6*^(zz6qcEKVC;^=?FQt>ys@!0@9B+^NSDlqShZ5FKV`s z^KCl@CRlQM;^XtI5cZ$W>KylRD_k@4_||({9#B3TaO}+5^YSe|l-vHmD~cYYt_5WK zHg(B5nu2v`X1{D%46D9E72>|%a-}X$a&`dm z9ad@eV(aKZsRG1JGqfr%uu>;uuAfL9hYaX~RI3a@WQTl)SVX}1lzrF(S`Y+>DXAvF ze#HV!wW|C&BTf}6TvDz7rJ#TPI)R-`{W%|KC@Z(dv6M`jghNY0n+ms1kh_jx8CGPJCgZ}6H%!8KX-VX-xAI~V#I^GhBeA} zTrgcw?EI-S^QfCW%xo(RV(%W5eSS;9h}^Y4zC2s{_+4FCs}Bvhr{PyB}ExcRu4gzuvFsyxt?$zz|FY!8=P!Z%)4AHS#8LysMc9S)Sm_T*)qO zQ)*!P*T!pUYw zN4boh&#QC-_)22)5d@=_OQT`Ol)G!0#}!q+AY$biNL9kLkoEtG4fSXBrHymOMrl*2 z-k_A%$B5ZZj%eP^$0_neNQFjv=&6)gJJQh@hnJx_r}j6eL+C}o=D_x&*}{iqKCA%) znZMOhTOup3dJE(uHwEbPb1uiT+4l&Yz^ z6&6b-cqoh-uDA6_psATV=xUSVhIsH>|BZb3W+63X|Mgwg4;4htlMp zQy+#Hy82C%SS(njW{T#A8L5cCw))M#hrZ{XZ(91zSpwk^ceB0zp(XuiBURan&^PLZOdYP&no^_=um8e zqZ{e{8W&B73G3#AIK^3AGCe&svwdLh5*}~Gt@VB2K4SIV1MM{Jt{WbDz_(h_j=@m3 zP-?k0d2R>R< z!08wZN2Dl;HI%X)^5NDB5gs=-5wj!YVd;DmD~5B}roC|rRz%VQd}Ge`t)*tN>Ph(E zIYR9}zh@^**;q;|X~NN~;*zW4UqeZQV8ak`gp>rsgA-tZEQN1@kcyBTzb z>|f#yG$NXUn?~%F?dh}T2tpGMTn1nn{~$Ar>hnS{C4p|oH;PS7n#liT0fFVp206y|U5vu2TV zPWBN|GLq&9XTSS{+7{80G@FrkmKD3iaUnNBQhY}zPU105k`(mAQ~BT=+CX)Z6UvrRfL ztSxS8YgF|d9_FdLM`Q7ibN}(4r-M`CuPCfhKNzWHp0U8w^&n492Bpu8YbdeG+DA$kZ=`)MYIcHkKdm`rw~*Vom=D5h(zk)Dm&>X5M4(=h|E*FvIoc`* zul!Tc> zI#vz563~5JVct^KdP!rbU7V=|q9ez9zsDN)$LzDmHaN#c!>Y=Rs6DK_Ci_pTjD1Z| zV)+F4OQS&nSu$me!|jvW8{`=6!wZ0>!{0e2n1ReR&Xt~=Vv&&3CMu~CIAKxLo%&MB zYN?QvOyng{8@oFGgqC<)7 z`^!8HSlIGqKDIRSF^JmuTgtY|8xAe$Nfby2jZmu^r-~lqnY5r-=7l7f@x)+ z|E86-(FwEpdC+oB&UXd~w%%DET6@ zUMUQHp{O%=l6I(RQW~->Dqiwjq8}q8WCT2=@JcTf6f`T%&zh&PiHS-H?OY*=Zgmj~ zhYX(+fD|P^BV;i*!$_>G$m6{&veAcq zMW@7hSkNqy!%24ZSmAw2*q+o<06EQIl_b*KadyTSQ;kE4{6ekcb2n3} zj2m6xZIew)EdLMi&HC-tARF%})8EPKo1gY2DK(@8w(?Dj4&nuz%}a!gW?L0ap{1{W zyWjAlmwVZ&?nXQ-TQ7O?!w=k?y7dQDZ_SkWNx_(!lJo*|mY*6_D%HP!(+-kQC7-m{ zcf8UGs{Jzp#;}Rt_!kksw8nTpXm~CC&m!eEHQR4y(^=hYAaEbpqd(60|!&3T>nQ@~i%R zv+{(%pY1R|lo15D?~n%y)U$aBHb7i|s1`Ib_IfYG`(Yen51xh9%-$MHBF?W@p$VPI z!nduGbp2LC?2fLLb=lYa2W+3I^Cq9k@-p;3txXisB*Mg2)0~=={+68ym%fOJ-Xx`b z7rGqQe{}6(GHwF3iWfQb_sejk_%8CZ?rz9=D<`HC`=`jniVO>V^^dw`MrqI_BK}?| zjLw*J{ht4#4(MzaVt(0dD8Nw>6%*hh4fz5QFNQ12l3o1x;c)KN`eJ{S;yWH5RnCIi zy6nQ`CxRu2r5Uh!a8>Q~zr$??+fi8QyMrUg?2!Uzqq5B$QV?$hc1SC6NUd*sAD^L6nG!9ggxTK5_2ZKfwL=BA)!x7_`ev&yMDacE4OS_rg-ur{P zf#wKaEPFq$qBMCb9)Z=ZRqy1IZgaYSPDT(pDaF1%6Vg>!-?p=rtL?X_sZ91Eo0s>W z`v6T0zsmz{eXzX`QZ_}MmHUMW5Y@^j zaF;vz4^+_&vxlT=yE_J+V3P{6Ya8I-9^ZgnDY~67UC-r*>-mV78!wdKny>z#Z#FFr zgXd#b&T=(pbxL+2gqR;>->238IjG*3qs@Pj`1lcZ1XY)|R6wn)VCV+$3(fyP*OE*{ zu+sa_QHy6YQU<9EMuwv$nuk-er}uZpho2}Ct9v@S2+4x;4m#ooQ#4jqzlRk3y!Pdc z-XDt`jLZQ{j$XM6g`7_>#sf5X5g-NnNO_p9PyQ+1q-P&-svCoJ^n|ilZ$>Z@EzU1v zdM|26wLp9|sF~vxa4oN$=38REqzO`58gg za}D3kSmuUvfGH^u8T++iUA)&DDX6EM*0~AG36)bQ{EM4@O83v)<9CuLjws)ThPRO# zOQJs*3m#FGNi8~UI6eTINLp8^?ACW$t@8Ewa;;WU{9KM+X0}{R3|U#GNCw^u3*C2H zVqE4M3DUAUjs{B}mL|4T)r@X*cnr;)L+H)^{@`Hl1(tjxs;0#!CG8GKL2`i|!f!~m zVwQHw5Vj+%RV|-T#WW31dc7e(T%0eC0aY{!NFHiybgRF4OdlfsSEMOy21)|TE1HD(qRm@Aaxg}nR|LxdI5zE5ixj~H6l-zXz0vrf3JM< zHq4CzcNgalfe!I25a;G;vE>4=;_9^C2&2NJG4nX4k%KG`%}iVcvP;gX`xwfb6%9+d z9z1|3pXmN_b$<5-E#xY8{YqZ!eJSGdU3CmvSx&W zUA2rP_|82}v1O`A7?Pajbj789xOcG)={OY@@S#$1xU`}11zJZuMfo+9@!~ab3-MZ& zD9fLQPicVWvQbopem|RfD1GfnM zDlK?!?qq~QEAT+QAZ{p_(jVVHEzl7Mg0RBDJaZ@#!*GAp!obwfGt?CD5}}#sX~%1? zufFn~Tr>ha5Of~sI!)gJlT|}yM^0Ba*)Z|-6RHQy^pxNYmOqEv--$Z^&>K0n!JJuN zYv{LT2j`@jduD=%zVp4=$&NHay=_82vwL;Qz1`wHpDLdyTO86cLHDyZROUELzpy_4 zIpdS6VDq2(YDW(*DvEj#%-skM_PNmIs~_G z@~^ER8E$?YwjfYX(Kl(~`wGZna5teKK4)UJ7B57>B?!c+Q3smK$6VFu0`q5z_)W12 z6JWQ+w17o0uV|W7uv8KRf%Mb1rGhS zsiov-czLmtDc|n#1G!80T=b2}HZf@rq3yg>MyVayxc)S&-s@x6CIlZj4u?XU$j}RZ zmK@glyc&2x48Vt+Iw{9o5?j=M1Lts4VSUCUIk}PU#lrSQ#HL)}xoN?MDT!Vul%g9f zJ4kka+4XOjv&2yjJa==;9&>rvtC1gb)8cnOR{uJZ{IWBM^?c2}LKOT1>(msa@LS3A ziTSx_=tb~VR+IdU<>UD>pZoHD+t|5>Xkd{@cEo1z^W|7dqUXK2xqF%FvYZr! zk(X_X6G)8D15#&My)`@D11u06p|PM2vA~C9cVt^)LqPK2_ua9E4$(ToQpMD&H`pxJ0 zos$p~JYiVZREjd{3wW|PFyR*yn%H@!&%C)&lQXd1uNL5sq3A6L@yc$A;g60lB%l>|8hAw}!D{R+{0BUyelyP0_p+~fbK@7y?B9PnTNuuDFsGP7z_N${^MYfetae#%Zw1Wehk3~+mwPVk&25NNUL}G<+w6 zAVMZ0yyKoHh7J$@$qN59IpZZUj0!caXgcTDla36mI{v*z`Z4K0LxFqa8mY}KzI=H4 ztCZ3ck+efqWdxq(3MZe-evr61K?mdVKUmNDSN*=vs7fQbX;DognYF6cXpD6erLTsQ zgYM)|QNP4xI$*+)SaK7iktx_%RQZwUIwQXtbj&LS7zUBx7z7%yxXH~y6~r-UX;fb8 zz}7bAOVzsiGjaCP1e0gU1O_Zj7seAJDN`{9cWc=E=~ebOz>bchf#n&U6-p$zl=+S5 zE!ptPlK$^9ZoXKN400mYmOECo??FI1>~4BI4$z#4BuERM8X#{+gaJ(@M41ngUf@aP zrp{8?7yKKL30q#&VT2wYi-}fy*O|pborALpsCsNwgwF6d1OK|_kXADe=n$=4|A?r4 z^!0tefhn<6rM*{=m5|sBG$|90h-m&x&Iw6sgHa(;VSxNI5r&^RlWL7z>C~J(CBe$U z)sw3uk@q$Phs{*0YSlV<(>&uyMBC*4uVK(RLzFn{}9aQiIs@IW~a}CM{fRO*=&NvG66;xh`?|ne8;D$EYU2*y%I-}IgC8QShiORry^KgehI$-U|o85e^=Ay7@&?r!L$+zKUC|3-=#F zCfzS0&qOwz7`sL&z_AkK1FIpp_Ih+dLLJc33W#uJA_~*j7IyzyD*3;8e4&tvswx~3 zt-e-nhwBXqF#V6rz+k2ZwY2yc z>`gp5O4B6jr{by{Pa;nv6R+~E#E?k#V<3`z;X#0dxSUFrOLIr|q{>!eRJ@zi_KSu0 zhhj>LQ*YuiCu%h@E5ck&Uti>HW+cW^6Y@ao0J|ijq@Ob)J;6VJ9$hoYg2}PIQT!%B zDO1-OkJ(Mf$?uIytlB$L0_o8ETRCF`qb1eC-?f|)bw|G?#>H$z{N%@At(7m&b0-hF zla<4Kxk^PapJv93ls*uUYgpGG)mT!lhGUn8BTKE!d#F1WbDn)c+e*d(YSEXe`-`VW z2OM9Bcj&fsR3=Z=;1mjksRo#qqrKg|hZLhs*jF<-HQ@AjcX}hqJ+#8cF}Zs|$Ef!N zlN#jXp@BT7SjQ_ggQ=ZOdeRT@b?Nl@4jyv$t-Pku8QA9VLB9A>A%Cj9uHFooxud5N z#;rOYeKjt0?oC=1@11V1xn_;=3NKYJ*NS$ZFlSL0w{=K5+AtL;RBxGmSzZC$d}%{S z-v6&jHB^_{J_i7j!|##gIe>X7yi3q%Wh((2}eR8=xiu9jI2J#?{C_ zj_=0ya1^SA>WDW?^2@G*!}_BG@MAXbWbE5XXt2An3@j8sjn?VA;ut((Eq|pqrXOOS ze<7kL+)w|v4AJKgPyEc3BG5D+ zfsn`qE+GC{O}RkruGF)~EDJHDeem^SS?VZ?h$UA@XzX-VOVzQAz$9 zr81zbd<#Gg00m?@%EmyNJ$P6N6HDn;3^f}%-xwaRP0pn^hFAg=CG2#P`s)+b{1e5M zr~h=9HQQAq60=WfNh-ww-+dgkY=kp3? zUyF)!uD>;h_pKE19_`(Aol@z9Esotop414Iku`ch&NfT-CV4gUWD!)oX9UOK^Q?UO zT|*1}aMcAv1B=Wcu{6=wZP8PsqOAYPJpAh*uVApQ=(6|i>JC`v&|7Db;;*0#??gGnvks1izH1jYM|l!s82; zHm@Z6CFTGC@aVPQddRholVh2BkUmjbI5mn0PciuoiF0M>2_JSX5$Bi4S=I&}$!uZ@ z86t!J%XoRK^wfdUN20PsxpZo0o#DwZH0AX7a|FOy+1cyBDJkCCWO5YLe~k-*t8V5No#hx^FqJbndH3 zFNCYtxh7pzXHY)g8nFFObm~v#>Bl<)o_9_Cx;^xEwiuNCUHl*OgfL2S&gkp37Nlc0 zm)A6Q{$I`fzZY|kPoL!M4E>AKw~$LCvPrG8qSJ_X2-hVhqG_@|m>%*}gpVgg(f1#s z(BRSVfBJ0ao;-REmvqw5mk+9bze$M--{YIU8msFM&9RtKts4S__NfVGC&&vf)CG`d zmoD~JZTVy21%)96y-RYpy|AssjU zDQ~|}%t5O{4~Hf%q8I8{Uv3Y|?8%<(A=vU_TfEDsqvy5tTPmFa0aT3?wlV~I+QWv_ zjtVIVY^Hp(1*104e2!Ez3W9;A3;2L|%ztX?s%qD_^6k?;uNnoo}C!{gbVNvH0AHYsSC4Fw_pM8^MxhI<1hrWnP=;CK~E&H}k# zvM?lfE%Fi@St_vrWLQZeqE&?PU)|Se4mN1)$5c&c-7cN*8KkVRtUA)(xAn0UK?8yd z5tua^8u}I_oWe0=*?~zRH4VrYaKDsjU~g!5nIx!x$zoaHTSTwQZq&wR7xb4BSTrhD zo{IBFQo&TlgMODREu=xn$rristai?k=m@aj%jk-KMU&)^iO--(eWQY5?w_WW4U9AJ zv+`mu5I0_ta3>DeCI8xJ;P`bl01Ym&A5XDY6UE$Ln|-5|EifJ{)bFb*UvAy)>#av} z5nY+q_Ld_zG)64A%@`{U5i1EE*W*~Z2F@vnQ=r%eeR)7WTV&nsW_6w z%e~(omy@M4aBe&)ZoYn>g|TGqWbcTpmbG#Gd~5zt7q9BKVN{d6IqP=LdY{(2rdfbu zy6uwTPA1PD@Uf%mo9k1wVD_?!p-CF%vy9MpFMZMQ&zeWhZ`7Eil+J59ti6xAZ3Qsr za(5`v3^+kyBY!5Qvui~TyW^0)P!uRJi`}|wzntJE&14V0UA(`CLA^L2d@KX~p?9`N zYk&Ed42p_j5>C}Es#fnuSwZhXoq#9PoIl(#emELRiwx~@wMdwRPaiebnaP9;WePV{ z&*nd|B`|KU^@oY@F5l#g=JZxpxqYle|yJTcB%aE@4A2&(<1;^ee<9Zuxh)c8N zG-kTQ%rTyWO`@iG#_u_thmiH6_F0C?zne6MM&#R<^g9jgR1u^#t#Fv9wCc$Q?l_+u z;Z51Fdl1Z0dPf1EHl1$FU@Gi^DvjKg<|(3|-Hf?2n`N`<>Bm(?NAoxq8PMbW4%oc(OHr*zdiT90ymvN>JC(gz6xN!^;+9(__{q2W2J~ zJSuf*AKkQ6Qk+)|YA*Djts6Ee>ZiZ+r{c23`o$esKbySXiPbaQX!pe6_z^QF#kp_N z?Ifbe_sZ&h;uj?u{v!6-G}{)pKT1Gi5Duvqo_yO^z~ zookv(pIM=hQInq-wK7w4Jnh!-zq=Qzwc>Y6H%ttw6JL78TmL(1DktQ$iOMNNzyCG2 z`_4_6aDn_zsWG#sd$qq<`owfcv0qJHD)}&234Nyg7#wTsdLogluV7bp*3H3^Iiip{Uce-%UqdW*un$Xck_ ztQ^;~o~I2%yqJV7C_lvGb@KOC0X9qjQa38-%XP!}K*iIlATlcqlRAbLQT0-O#uCS? zLvlo_{Ru6b~=F&;*>_CijMKeO6*`?3Hd`lH*0*#0Iybhr~GfzH3h70?^^#i!wHUH30mdZ#yMQ$EKSHxH#EE z#;f!x6oyXTozy6D92OsXRU^(p!+p|{18xk|C%uC<`$i3?fBa?#>wLO;%ME& zLYfm0;E=cvJ89Kr#0{Y?xHpgMGL>pA;9YJ&%$60$U~qLx5`tzV zB;#ptBnP)c>!KDW#9I*5uNQeYNkSX&hj*#6#iEsI4kgb=1Om5^hNM_4yMMtsc$2lH zTOX5(D>1~LCdU_~!@-;kRQs0Mn5rKgnwnQ)yoq|)l90)`Q+yZEn@e+|ghGO$bFI%9 zKb@0Ztuq{ODs0CC?QifDp6h8S5$uI z8POrn<9FFilt4qjf=U-(9Cb82s1WJgzGv?dD#ba}Gl!wDs#V}*sF`M-@@v*Ivr64{ zYI|3m0hMpR4bhg!-h8MoDr)W_19f#s)`_S9^CFGJTM&_6s>G zhEZcPF)kao_>yr6YEx;L>`nL`UIoKd50(clT{+t#172AL+eKZy#>#xr5E*zWb0)q-=#XU5t zp;A;!_in}n46A?dkAA^Vs34Kojh~4DHKvNlEDv~?R(ah%;2C(KA49oc;ysWa*_|AI z&weuHDO+LA)W{JJsk1xE$Bu&{u*pBI_<>*aqa&QnEN=x%(^G^s23`sN50){Jj*5Ll zCqW(-6TAZH@+XsNtmr(<95`j128il<+nT0#&Pb8Hz3XE?ceZBMz<@#`p9#IS-)TN1 zuw%oeM+0-aLvySkM_&I%59 z)2b`>&0Sh~-$gM+ zxnJ$AU0IqMh3YJ)+J3o1D?|T?F5&UiIo{}2%l}Il?vInJb%k7&VTnq^g9k5aQ%0Zx zHsm(M3jXynIPH|zfPE#0yYf|6C&2>z{+IRoN&Z`6teY)#&+*)SG(Iw+K{6>~-TCh0 z!a>H~$#FkI`=5Rt2FLBKTE)N*S1UwK28#xXt4|&UCNee8m7GH{lqIJ#UsLrK!VkEk zO+wPrJkc$B4R)<5eZLg@05hg>ts<1WJ?X-u;i*ZuL`eym8z7R@QEY`%aa^sPfmJJ9 zmB-29rkRG&;h)t#tmiSVC$0IukV{a?twm_Y!YHg>v0^R0AjSn`E{~-f7z4hSE8$yKf}9?y`PFP$ zZIQs^F!(0=zm4J-72yXMv&lB%5-0p^8j~I4&87)K4AxX_5xlG;bxYyBYJ~m!9cMQ@oxszBDmSV*F(<7% zElSLScf7Zi@Q@S%q08Vo|RBJLW&mXA%awQd}-xYL4Gwz5dt$+-9Ke+n(qaMSN zK_scr*hHl~nKbZ{%6lS7S-2wPXQ{Bbld2uQ4yVYmSE|mE=y8aBAcMv!&N5^|6FHXw zFqO-9q<>}v{QZu^N~_|g@L7dtv?`c;Rwr!KGJwT@9bW<;1y8Vj=mq_tWZ9^3E-}%< zYsFTQs^-R(m~a52q|8gp$cebkNzzn^BgsSOyL!@)><>k_pM!H4@FuF2fSGVq@Rf}) z#T-WCTw&6zjA7lcqvbDUa6!)#zj0!D&+Ijf^vaZsEKzy>rdsbX8pZy!XRq7i(Io1oz61Sp)PaME( zsACF>U1N7;umeR-?_!yn53(jKdp`R0toVmi%25figwes&8h-HDwf{1Z3YuPw)_WrA zJ}>V+gZgMamV>Z{sIzz$`2Jzwl;d%8S>Zd@*^zxhxwv1Qkia_qU~2jWoScH}R2|b= zB1xYi%%xr3qZ2=n#tfK%BHTu#I_AIkttetL+JQd7$kPz|E9g<~jQfMET}+o5KwGr} zBfa(ex04nAZGOB-;^faLR6%L?(bmVDcm)9`?rdoPhksemp5o-?s*D{u#G{^^HZ~XC?XVg^LFLoWi-2x+$2~?xO0;I zEYA#UtAI-~d@?CmP31_%V00H|Orhp*2++)&*rbP;vmDa3mk0d8^aP^`rUcA?XWT)} zJBDh_gar?T&DmW`Tb^dzi?3Y@Re4SeXa-B@5@FIcwyFQ=sxdcLal6EwKZwVkwo80Am3 zVxkjeK2rfzl;cgClymPF7nOEe^Mz70WMW{mh+b{hG-by*XHM+LZzHYWGQ}!N_(^RD z1BOHUOHl@v+=m7Ae^Uv037$^t$=#$1uyQ`L7j5oUQa7zo#fjy7lA9Zi?{G%vimL4Q z#IpVQVVOxB5~odv5|SW>4Jd^4uf8UauTgIO> zCRuc17(ImA!vP`#+>ofRqOu$nlcWqqm>CjeRjPK@!+b26Dg)@WqBTZ|ctpw`V~uVz z>^lE$$@rV}khP2ytWSe-BV?`9q^H7^Tuy1VieCsUO^uq^8l+dReFukAcjO^;5k7jFFCMHt5^D7CyLWW zLzrilTEFsT`>Oc<@J4^O`B_zfS~js<2KqH)!$<&m*=1@%e5Ot`kzDgLM3+DY4Mb^K zTbqG^DkyMKvEZfMqq&fHAc(cxQK8u*vssOiLwIBqbA7!lXq};G>uW~ZR2^I1?IPIDo0S|D z5liU(1H*gsH7luNsa(@qUZ(}XdaTET{~q)jIRES55MvCXL(>3~eW2LOr=ERMFOkmG zC{omxsX3Y_=bYwsGlx~l*~+}{peQcGnIdb>!&x=y=q08Tyn^(R!p+8*!wYl38o<5W zArO`V@fqbCTaPrp$x{!ZR2$3Q!>5}Qh-!4uA&3Vhk_;b7a#f<}CK?F4`G8aPcsQQzn}|?)G^JtGdg|t8@1~D_2UMQx2KUcNZCS`Q|9ZbOP2lij2%FKaYw(c)ITRmly zw#EtT&7+%9P^rqL3Hg1Beh#KWO0+0`1a{ag?Im@Tsz8xn>(2r*;339~_0 z48NSog{UEOk)Yue!H+7ix4wg~ZaF7Pgu3r5B341}uM zSPG_?a&C@zVeLs!G>e*RVPq@VjH!;#LN2Y7$^lMSEw76Pq&}EEaUAWtbjAQXw*nWd zVwjX6y8XZo>A$W!v2N=+hxJ+7pYFG2FLt!|2y!RmLFcSbP-G7R8r97M}y%z!a?wv{_SV6vBd%d zR7T7ijoR7%#8>OACl{ROI((&-fu12_f)VGF!e5%+h=B?hn~fO7XSSA?yMS9W#``v@ z;sE}A!)2_N>t{!n6`3*btVRXl)jD33?A)@!Z1yb8=dHZa5!Y1e8z0yl#75{X;gKr9 zqsSy#%?%j-VnlTc!JTbd_)Rjk@Q&`JCEFZ?!CmQHZEl(2J)|)`?gbLN49Hy%tkb_{ z@t$|1ruMP!Y$NbuzGOUDo^Z`(4bGIN+Zzyjzm=VY6sV>Ou3bNIUR^E3p1f9|kg@b( zN+XO3YjZyB>EmrKNp!Pa6v@FWZ6aIX#t9Aqg1a{~?(PsYxVyW%P3L>>{WJ4s*1ABiOS4vUPMx|{ zyQ=nH^%;9c&j=GQT-J>pQeU^Tjg*c>;a((fze#v_u^)Usmb4(jk55PdC*N&TOhG(4 z%h^>;*sDW}F&$=>FSPGAEkyk&K)oCWkH6KRY3QC_-eyQ^_@RqIX6Lb%XN~cJ-rK6H zRmiZtzRg+>C*{#W5dH0FE|T1Z!}0DCibBHYgo+(r!2Ywz7^ZVxxp7+~@ZrCN8_1o% zCE48Q44gxo^06+3OyXLg3PyK*kiAY(i;YwrUKM3F2(U(YX8Q3Eg;kdjs*Wso^Sbrm zZBJ{tU7Xl=a;P-($xNTt4(-HM6kPI>GJyIDUr*FZ+KK6| zd|)W%@{HgO1HU7B+ zi5mGj&JH?tl0Xv@rg?ilxan-qV(FF+w$J?b%_=;=(^ZTv71brK}D zXur@1Aq-+5Iw$LBVzi2?QPmJGFI*S)9afL$BeVpQ&V`X4&+zuAW<76!2|*x{4PP!VF;`6ikFNG)D-E!1_e0GxVQ^(@+a_L9$R|`BniLBra=Ph+96#9 zJ5(itbNGNpF_odr_cyB0D4cp-P#{|sC6~B7D24GN#_9~+%&_E;&ryOFu6fu%Icdxzrpg0wET*W4shF{VQ zLdXG?Zl_<8Z}sqOd!qW^(vXRwCEfbVaatn8TXw9w)rWY}SZtzS3%~T`D>xh+&9w|1 z|C$@^WEPyJm!>)y8+QXES(!ctRT%`?>2X)|1uyY4$e@3si~4!S)We^}GLxJ8`m*B6 zPegSek2lI;3!$XU)+i3=pak6>s>jh1AE{=5zLpQ|8I??&GG{H>BF{%y@2u-#jcbfJ zV-1qzzc_a02g@(WBl=szSG%c1zlSqE{(n3(cJ>g}U_$edbW5SY=7p!t;UIS67HI+r z%lH<#DPm{+$k~a>bi`Wl2ojT+-H?j$ogy#FIYd~_I1SJypQAo-bR%LG?${KmV>hU1 zJG>lh=#;IVr#dL!hA@E?&U(7#kYGENl`O?Sj&hC)e3PxcV-x;gY3QR`BEMM z1J?W#4}bshTJ<=Fr^8dtkKH;%Qkhga-nDiQw|Zd$77fqcPnD`c4`}j>-`X=~a!b_h zO@qKm)W@@~#-eBS$!O%pp%Qjw2t6#?8M=(s=!65lsNDFzuT?z_J0`gCW3 zMGqn?N%p8fV5@myV7KSH*ABc>SKOttq!CKzLjB^$7SbxnHt?@9%@U=Eqp^ZkW z?OL>Ty8(7=zJk71256Q5tb8RjK!5GsIOdGt39cLKpM2~fJ?EJ(f$DO_@aS{`zg6BQA8ZJdKE zA$ZJDQjsv{4}Y9$D(R$m78lbzTGc zWe)^bJ!>mLC4QCc_b8)=iZN{Vfwbp0|8HpfoD(V}S0jTjv-b4xS1nh`IOV3iuppm71a zLSOI++{TVbp|}f(RBQ$;lc1Xs1R7n7A!Apap(B6K8dD;5wBs5l$6F|Q3EoA~7&Xyo zcQN?8IZ}TA;PyR^z{zEm8@sWz58TYOtGKr7FDtL1n zQ{$LxD8|~W4uq@r)9KDSBR9;JPxHc29dp-9iYXub?f7jj4``(Ib+~CZYzC`WaoQ0}%ZcF_=uqgo)Ci(S}Ke1lxE2M^oC<1FX9FwneYEl)+$U25fDG zul=ldz2~p%^#_?9t2A#~PW4ZM z41D-?x11u_eS3I0qHOxzr*UcnW=a!_rQjCOg|-SHx-fNt#Y3XI*dCwcGC+ep%Plo4 zX&liNPA(h7c`p5j3ce&aj(O9!CVCi_lt`mQ6pZkZ=)JM}3@c7Pl$^%3I@EiiS`ZXn z@ptIZ%x%J->d!17uJt=$1L98g$5;{b<>Ewm3KNC-T}}jAb+=3Kv5tUt<^$7@l# zQ=-Y}M6#nWY=Z3#yY#z|eizofb>%)&YEb0AuX0sX6e{=u(85R}N9lbb;hVF5(I?h67jKuo=#j1%$jSQ7Z;$PJ# z#D78n{9kx;BhDL;ek8;Z$r98CudGO7iQGj7B|X-}yy&1&*>lLfFRFNRcSUcveK#Ta zGdvr!c4<#>Q+O4GA1$fjLdB*04yh>g7x96?C10Woz=(HH^NMI9!J0ou9oX zS{kz=t)+860n+j4q9sT5uY^5v-y8t(Z&zngK|+eY_dgc2_I?KTy`2OsXfa2sXs1SW zj;C|ZU{E7k?_2?ah_Bmy7dy3dl5J1K&-;FiDzB%73tHn*8@bL-2Eso5NHc1%r=^%a zbLwdLc+%awjjvPR*K>Y%%{~n17W#}#nI^PE2SugdN3)-U=o(W_fc~qzi*q;&oT8Y- z5k^W2JSlusS?Fl))`Jh^Ydcr-*)}&rRO~jJZfS2l^$4XSzpx4bOL(@P%Ga}W2QVP5 z#8hLXeR9}hkSMsTTOGe1-{#eY_>7=@1T(d1?f47E%sV%b2~eWFqdyF5f#Cccm? zI3RyC!zY1L$2o^Nc?+$LEBrG}pZchSqt{tzk?=bJPrW;I%o(Bz@@`s+lnuSAvtFf& zWpO9O`dzoJ({kB@a`lK6@r4MR-({nUj(DzzFfUI#_M(O;!@#kXVdwD~AZAW5DZ~?= zB+PHFP3_QXfDFnIO#`)iG|k?rYZ=W^08n4D?=93-Kk7`2%*{HZFXgi;Ix_)k2VVuX z?s{D>1U>jBmx>e*+|BN^zRT}dX#Z%!OZeG*O!)d|{-s7Fm_sU@lYOUjHyO~MrFsD*1~K`6({qs ztwOHiMTj0#P+&IU`uZ~;A0l_Sa;b>^T}Q02OkMs;C7o;^;m=N~-|9kDD}@1SC7~=I zqH-_-=?y}oShWVeP)^WnT1@VWsh7;A>T;mO(emL2SYYYP^khgn?X}HCq^3)n)3XS7 zM~KJKdfFnKfWuL(01}pU%+zW@yt6ETpzqq@Kv3 z_cSG`aYvf(2c1J(*W59mFPBzSUQ>Z?mjcf zmVu^6d1D>4U~%9!62IuDUEM!vi)zrz{F~BWjQvT)|6r&43!=T@iS$y>iv0`Ju8W}0 z`DJt5Y8F>k4_j6fKUmSz0n15eF!`YSa%C((F&It2cf&?x{|anzgU6`={)?Ds$r!jDky7_zVkdL!JPB z!u<5g5^T20D!2wGWs(P)9 zuDnlP@=Gow>Fig?2nPn+)RftHZCwCe479 zX*cdasaG1Cj;hOEJ*gBB<~xEJafmFm;Pn~AncyuxcSL~}rz1${i9J70O*Zd}0GvAL z4|h;*061dM*t3ezLp#!6-%ZOw*ELtAwS7MRnOki?WZvk4s5vly>LN^=I3lU}PyTT$ zMN@^ceufxZ+Wn4al~OCX=bI3*{|876Z0f;Xg)&kt=IPZQYnPaSs!;XUpq2kSuap_0 zr9ZenWspfk#7pUyA=%-2EO|=T|QE;aC|F^69?pL&#M567-(7&fUfCZzPWE<4+=K6Ni z9Hx;Llfh#v0gA7%5pZoSAu&q(8w#DXL72&-Nd*^gE=;NhySpL%%TIm3eZTSNg`8c{9j#*JL}%a=v8~G*%8#5lb^1I$F2&~e`$dOL3}A?MqI)7} zxQX(`=*XxHFK5@&l_@CXwh?9+9DJ6Bc27*1#84-u;DpQ>iSkiN+w}I*YAn~7GfEX=?ZSrG(Gvd1b`ajs` z_`IOS!7Bf8NB>e4&a$d${_AP;fBN5SUN667iY>O0)L^8`VG1ROk~M zA(U-KW}t6FJD0Pj88Ssv`UCWda*W+NB`01Ad>Ol63?EhZ{Et#6Rl^^Ae&#`8XW!Xa zL9Cx*SId75`rG0!Vf0qa#_BcXe?PGT$Xj7(U#^Kto_jGP-6*8@{?rj%*A>z$Z&_6A z5nUwP@IKb|yRPK^^vF~NbaDaE-=Qoa%!4q3PsAAz4Zq=JtYrWEjqh(AZ;|Jy#tUD9 zF*zD!LoWk{(8s6(0Js`(yP>T$0=t0+v_Tj-Z6AxVBe7k)3OG9yxESO$rYa{2+P)5k z&=Kh~ib;xlqX2BDFGKOIKbTdFhrY?+lQ70H*M)fqkp+E-WzN$if?1S+Dujup=dOdg7GVoEB4dGD8a{w1SJXI%29BlulxNJL*t^$&o57x;I!tG09HvwYk!4nvj+m zTq`cNh>6zEH+oukIV%qETWV{2@7nL${7pim$Xt(icFdXd8Y?-41qDYbVg%TfpRcbu z{wjGUr&x9jnKU}?pcvkFo4e9zo~NYicqbzl(r#TxI;4_Wi6!1FFd zk29||{-5`InO@OrFDq*+slvcl0m!|l=IEE_XP6kEgRZ)}(JAd2aH;-zgI1xBZ4$V! zle1mTtG+0+K|BeRPj?%=-8r(I{xsZ6p-kVf4Qblk^n7)9>>b`u-E9;%6 zb2Tx^HBTW&Q_%16e7AddR><>@@LJJ3(Z9W1|6Imz3z(wx@08Y21UscZDi-Jl=h#M; z))`phZ9Tper|`+GEq|RUNkY<~6LGa^p;s+2Gs`nrT4NR++6%Rq{-NR!L5I_$73BaS zTx-2o{Z0q+=O*^=k(H~HcjHBgB*&?lu$8;HR`XFi|CKX(mg!6qo^W-bCS@L~b zw9oDc!Rl>&LtXE-Bd_gBbKP0Mbaqu>?^?T08cmkBqt)x59C3li{XG87%LjoZCjCuK zwc!S3+G&mHfRh(?8E-G^4ms%_O({V18Sau$A>VBxNrVgK>- zqvyk_Z56i*(v1il&a$6Lm1F?SdD4|TdntA)6}=ofwU~=3almvT+RhcEHv)yKi#|t> zKwCk)9}?qU%(CzIS*ceG8ZcyGo=p(c8mbw5JzmwpB+v9akaeyD^cL%l)gnO%6$b2f zvi0nIY(q_z)%HQAK_FLNdi+n=nVmYL@jX$OO4$Nji-zn!)%nol)p(@6d6rjy6)qwV zL{TQnieo7QT0F6x@$w0uMBt0;!IG7ky8bKmb00(jN^rZ;UA-RFrLSFDmrGbkk<29q z*A{boQ>m41fq>UfO{}eokX_cLe9y8ZeZ0VU0Y}U$HsVm}pk2MZwICHkPuTW@4}<-N z&~kWlw%5$V_jsrl#Z z1i_9ZFCAKT;F)|p_ZZow4#&Du9mCB|57^mZL|;f z1z@F89zv}`5dg6gD>`)uhfqw8qz;?nM4z_yf3xK8(N%oD`PJ+#biMqUDhu{yyVwZH zB%XEv)rw*1r&_O-Z#g9UD^{TAv=8k(5(QU4%0r~gz0|+8KC4qB#^GZ}*!vK;Y-5dN zN;sjHr8Z?um$-~qs6u6t2@*(^yvOG2qyIx<@I!|Lgz_xvOdhdVKt>h$L-pP4Tux;K zSE&BLF%zT|;P_c;#|-WZ`c)_}=4ZNJ%IS>2t&p!{>lSzYJ7Ix9CH~JX{q`Qz5E4NO zLGkE0P;Xt2u$Rj;QRv z7xW+HH)h@4-QCLPB{!I{@o_c!#Cp;z2%{?1JTd>_-y?CouW~H)6zqzNi%W|e@i!Xu zO*g%ZSUZ}BsQP{Uvr|5PtNkx8CW>_m={*b*AiXTw8+>R1u9ESm+1xBr(eC(xV53ti zer0R+&T|r`AOCvDpPMyyA@$VIA`G%M(Q>klgK|G+2wdYUjPx!WW(VB`jTE(OP@4ZB0*n^m#n~vIpLCx z&+iXMkSS!FSu?{jYvKj+qYyZFPD?fU}i-*dhfPjT@ZfE)54)!;sWC@g$;~e znoJoep@2{w2S{586CaY zvh$`Wt(u>$Rs!y_e`aQeJr}P43QkQ;>Cf3klTg001D^*zGukAv0$(s+$sx~sQrg>< zGfzAkrOac#Tj0YwVw3C1;_Pz=gp#?XzhR*LN&jqfx}bsQ?xo5--FfU$Oi+R=G1Rn*cC-0vaVz1$hrz3Mn0b93AsNf8`yjS%*_ zwH}zq1a4F4H9K2cy~2{+L*2QA!QT%`3w8GyZwf!EFd4L3m_V3Go6g#wn)`jPP06xuOcxN|j{%Q% z-rJY6J%2>feZJejYR`LFK;QNIe_jz@{FTP#U1PX)113R&2V1MxmoqQ2z45Fw!nc;J zd$_+U&$G`@t4{``-j!F#yGoFdLtqN~Y4xr>DYUuQH4-@P<-VU2+B^Wfj2E~XVTXc< zjGk?5kXAv$6dI4_cc|x?hEJRjxy+5zi;g=lftTwk*uJ+_;7f(T&9oY1Ng#Trf)$=K zrOnYRq;Jt~t$9aPn^%VSV#5xbBz8cr@vUCG_H%e9?!Jzf6T7_;zY9Cy(vl}BP5XHt zb3HMQ6v0~`vroxR<7ItAd)*PM#r!?9&%qbQf$WC%8?a!EsNv&fQbV*Tl%3D8t|w_| z>ekxjuLgTy%sfOQy2Ndzil8oApJ6!c?4PcG~pe`g(gct0J^wa+>Vc+Zp?^i5E# zoV~s#6=iNh(iGS}VaUJw84Vxxe0oZ$=FfEdh6bka$OO{~ZAcir`{O}Tid{JHej_x6 zh~;%7l+?tw+>1Y=D9a<{;o*e8Av6jISzw-7s@K2aU%y{fPrvZham{k0gDL-Q7b36g zvG!e6Xe97<;d|5SkH5hnuaME_&cMBKr|0{N(~EJzft#Z_#Befd-1Vlt%&mgL`zy%r za>buB5^bn;RHXt<90SBSgW3~W@#2@Z$+KoH;1hQpWp^e|b*AbzrU=m!Y_dw=aJVmnG$kt! z@sUv|*0vp2g2|vNlB(CFBr!xkOU*loh-!Y_<@K=1mc6zRP%2>jqYsB=Q&&FK>59Dw zQgKe|+BXFo2@#pQPvU(vX^70bZqDOWvJRX)d{u05A!iv; zDn#k01_Fpu#iBkZ%-2wN%+&0>5>IQCOeDD(V>UmU>}*>#S&6Q4zj4$!tdT}n+g|zr zP!0%MeFb)+2TKXks1FUUB4&mkzzj<{@zK8PsXBSvlAAeqSL1O_RJDeh5Z6HB#ib{p z;h(tmq#aPt3$K?G0^y1z=CSNZD(ToS$AG-}G02>Vu~X4Yd#+aUl?sw=B}hX3TxGtN zuXZbrhTz8zV+goTIv`nv;tWgr5^F>`Z=KmynBv(aTk?%1hR2TE#Rwk$^2{4*LC>0{ z%s?O9Y1BWS#C22-4<`Av_h=T-T!i-a%-HBsIvn0&X5*q{^HhF=$s22Zjrs0BQ8e0L z+@X8;=fi`C&`l_CFp((+_{g3`0BAMd622M$3fLe2b!(x7Udi{ELbvnErkEez=3`BT zZ*wrwao%z;f$pEHj3|pm9|o}?mImC;BO?JE$M_zbnnt|M4+slQ&y$gTdfkc<7FwPc z?*-o0WbIfPKIzO2;4Ph2KObkk@ftoo&LKv>U5)!hR{*z&VEcSeowBxw^iBBtg)iXN zAfO38?Q0lK<~lP%UGO$+9GD5=uj?RmKZb;x)sg|0gQ#-g!Uu2jtbN<%w3bTuOf%vAmPqsG^ zhB`W8H;p3kqqc@fx&}Ij3-uK7Hf99wNY)Y zt&zhs58Wn30?mD{!+nBA&zF~Mwr+P7MkgMqh@s-47}u>JBh8t{*$MmG8#hu<(gXwqyNOi5Cey)6aieg!s#$AbJ#)gozVA<*C>*K#|;73>cSA+ks1_uyeE z$D?UYX8i7O1?7sCVn%S@WQ6X~Pb9wz7=ILXe_dYMieuuQqhK?r9oIZt#%`(KWx^SL zu@Pcb;W}#~1*xxdQk&Ug_WU*=7U+4d%q{5j9u2wR+7i-P`8I?)NS|W^Jge}65&k6I zva)PXRyt|)@*O! zkviLWJfRrd0*)(`k2fLsva-7M>Y|a%M2G^bfDcJgIyx^M>TvSL#uAAGKv z55rY=%(t^daP>@R%EBF3o}j{QTUR@Kr9j;6Y7OGHRa?f+`S#7>G)7rz`%l8hnu*2e zij>&7<8ctYBqqI9h{8hCN0|dxQTl}5p#^QNxrTw82cuoMA@e+@4!Ba-V_kCGC}W!U z`I9AG@FjW1_FwINDs3e4R6gBu9HbFkHt@G*otjfqPxyb}nUkw*_H3wGAgaPYgd_;# zF_N*4(If@AHR|oxmVc3je}M}4BrfPjlF4fwM4<%%3IAF6zsqmWa`6cco@l6dhSrNmt=Hd0EWvavJ&z=2Yl}U>(DEDUB)D|%NNFq=-#8w*@357vh>a^4 zXMM@doWq`b%pz9&8lEr=5BPDHcmjR4eqlNMY0LGd>=Qkj{~D(M`u>1CWhIS(d-&1z zW5vgR+gQMP_&@sP|5*@7tCNT-Q_=+LRpnw1c(E)h6{b<=zO z=lGy0{(+UIIN#(Uio#4Dc#$2{I`d`vz}0#H*9zgTaM14=EmMz$RCfPm2!Fo^#Z`?% zGO>meM0H74qZLqF4xEzE(XXyG<$C6w`0w zbf*I4qJoYUqf-T=bjGro3?YQQSw1is={b7zZWZL3rKy(j^0*Dd@NxK@s^Ft0Ms^!j zy7j9^WoWV;=QQ#iM>V$rT1`&S7s={yklMvB<#yN;=z-2OsZAfjcT>q z_S9>BzgRc1Hwpj0PuM>T3mXdN{1_AZoRYUaw%PzBA{EtbbLB90Z=O(lxOYNkW&yb@(9(OK2jmcba>Pn4umv*qI zKSp&L8qcc6dTqP={))hOT^&u;ym65xNu8h^gWT^p#Pr?$?+?3o&IIMxgH-w<45mXA zhfBEfiUUt}Rv%#vJuC%0T6eJo_|Pj-xB>=tgvKA5H16+%C-z|MDbXOkGPk4TO`pGQ zurqh>yo(S?Q=NX1z3r)YMN<7( z5m&qFyZ9_b#3t;;THZn7r-y^<^lgn}SOuyn{Oc^KFq19b`dwB4cUeyi8TXQJ)qoYt z7)bGf{&_)?LQs&+=2bdcyq7RY45$6}X9^6d6R~g3z*V`G_Su!7NAG`CsL+Dzn*A3C zv$x`^Z1Re+;Wea~$9r_@os>PU*`@}=`e~O~6Bfl?k`$on_g8RpsfmQOP%3pegs)H# zctTfG4Y38eQ76cCc;*qf+6`K(pK*y<)Ri1P)4kL zG2*2KM@isZ1`NdL(B*L<6tgAhO4Eo#x(dR`IW@g?0>_nDC!D|6tO-BPdj1_!HYFM_ z;#6zLzPW+7jj?6$+JqpYRBo_=6_X z?IWx(alnApbPLX>5TTE+r+JGB>Jhuj{nWeNnU5Nv4bQ7d<%;&3n@p zMHXJ{szNfRnMt(3Y4nrxByP(d%~GunX2X^aIYx)ZH|woYl8+6q$7RX+i*j}8$7RpS zuFQJc*4~U&pVL!yN-aMdEG2O0Y`AGt{Mfs8J?e&8o&;N!YAOlLxjSK71WuI5W^_8c zDiRgmJ~%s0*;2|XP_DBpoknq#N+_mvwmVsll4~%Cf);KBJY|)<{LM()`HPF%I_2bM z42-F$05KmCAVdED+hH4@{rt_*uXkmVKU!*fpetzA0LIVF3_s{Nx|lXTwkIkrQ7LpH z2r+<4g6`wfeTN{P?4zGt4%4KLw&rim48l9f+y?Lc%_dCHGz_6M|fb zh(e&VnN35afMa4dyK&O8g-tXpUtY8myx=iI=&}gLwXB=_+*%m+4kiA){%Eej;Lx%( z>G%Hc%SLlFZ;e4h1XD!VdFv$$@B-4}1|fH=C${3*(S~753pA??GP4OnuDw13+Shy1 zv@cp*EH=Ton5`RrTy4ZiUv*a<-}x>#zSj)%tWEj!EAW*CJG_o;>N67~AaCLbQzULh zAx3Ag(^Qw>7FudM3EJZDlembhOeRfErE|*WW7KmmONVYlIM$2=MBnYwH(v%kb zIQOZ^{oSzU$BGZF7&eh?3O+6`_Rj$E>2H&Cf*QK|IasG6ScZdN`ZdT|*~^wT{JCUi z#A$;TmVyszU|ka^bN~h1lI3xQTv=oRHpL5O=1$XcR&9|aoLV~)%X)vS0+sM=I^UD2 zPxXG82}$>H>ak4}+e5Lhhv;2`;OIos^7TCAlSr!l4kS{tKXGYufU<}=iPs%E#fYcK z5;eUPC=0NEyGL%WV~>oTy7Dej5QprLQ-|AZPurxqu0xb1VGI#{+av0%!?-G5pQEfN zrWcSj(W>5r>NV92Q}X*45?&Q8I0kgqXGvcgR&)jZjkv(^LLo%fMnZ(aZs_}FI9a8) z_j|h=T~|@uG%pj#_wiQ4YaI*e97!QS5`ZOYPt1<|dRP#8^^Yg}n;dA!KSen3r<(fV?f!mNKIU@s!9L_S4Gxp0`PUF;y~ z%!dy0b0kV0?z=>w^V37A_OxbZI*xFiESx-|ZbM7iIUI&w0Wf2)wt#P+nO>ly_FP+j zM%`x^)f`9!te83J3f7@vcRAZQjj)|c_jGPKY|5l)kJL`qdbzO4gI#dy53VB! z7zcPxj%aMp>NR^f!S;La_R+hYQKU+(c@)RH#|OYsR*4@N?Z05ATg(8ztInXSveVta zn%^&IZviZ>x{01PGGKQ`m3Qv%Snr?Xqc~;jJZtF=%!*#u_L`etrmQ_jE2j_rU%L8< z@^>fC13zXgIxCcNX{&o>jC!A=F&V~noVejkr zky<4!Dy=)@&WP)Gm|ad&ESd#p_rdT!@EeN6k-k@=`{;k^&I&-xS6+dmCrRzy8$W!} z#cdlKwV%i@`{2JIrZ$WcJ>B?!`BODJQ=ZyfTgk4aL4tC0=Q*$6LQQL#iY?im$xZC{ zs_Ok>RQ8DT8W=GeA-y(obO$@Mc~h{Y;4tjd6jbXBIB|4)aB?1 z#h_f9Mf~vPk>9++o;<%Inv`iO*OI%b4zDoY-ZiGr^$z|<_9W$Tag`&nP5Z-seENd9 zPp(?AqLN6%e(IwC%bI>SA~6&inS5{?<%)4~7DbH(ct(mZt&f<*pTUK)HK-eF`bp?( z0Xc5q1!MY1H2!*hpsG;8 z9VIW@*9BtuKZ}xMxa7jV3pxxn4<6Ija5V++o_T*xLu8;)T+ioZ7>4maq7I##Hq)(f zF{i=1p*;IedXUv`Z~z<>E3%k?C-vMRB(3oFO2(wF;+3$8^R?{)q(3}!rV#RYU-S)5 zk^={FDn`(ouP-9O)_MFsj}68}N*$|pBPwC(t9Jx;mv*cjAEG5Tw6OzlCs*EkwC2H! zZ7He_V6dHGauhMup^d@YYg;p#@frPwy?Ct1X8JkcI92Lep@?*Nd9+qur;Ool(p+y# zxJdo&pv@<2DugHm1c?#a3bwQgOv!Br7EgAPWe-Z2=jVfp@OF);!41-3szhmVglBV7 zXKthU>m3k>CTF6~n5W5}tkCnu11`b|RL>h#(mYC5IE&gQV5RxjL#1^aD-e>TcWd(S zSB&DeiTYgD{kkYg=`X%XPn$!88y`I=NfiYY@o*cmSu-BIm8RrDA?O&<8R|BWAmlCv zxj512$xd?#p-TYL5()d_iVY0kxOBWcq;qwqMi^YR4i7N)VGpEp|7?_&VK&#vf>IDl zDBiWD$7h@`3fV-1T(G?P3g*<xmjzCk5Ku0AsEohrgl5oSm_=D??%P~jj48*pM1F(E-AzV3Ln9782MWVt zrdyR09Nau@+#p^beJd#MlDwb(aIPMYNex{0bRT!HiLUO}%9>Jn9_5g|30==z^Vf3z zI)&M{-fq~%Op~fLtFtrSOfhcy)%^bQ`=WhOHk0$hFwpB52 zIQ|+dBzijr?bAJm@}|n?KPB&^WvD!N-S6wu4Z@{xxPMlgS&HMxEsQ6z-}6)C#}Atm zQn|Zwu)(!0j60lJIWG)+6kI!(;R$U)^p&rNx@ZQ#<#IMkeldb4HeTAqvUpt7yOLi zHc@vJRIyn}ve`Ur7Ij7dY7gx$M*zVP*iW`EPvrWKj9H@r8v(yqu;orZ%*88K)W6oq z(?fa+Q7SN>3+4c9B{A&Dg`@-Fq5w-orgoX_jqcV}+lO?ciVX6^%OKfBep*GvF4Q70 zGef+;dPbq9Qi=Yza@ml1`{d&)pY4P`T(2oQ!H4w61}iqh7q^2~gIc0WzLS&l-K6o$ zP`luYB7?EVH2JI436yn4uzz3?A1O2Rzj7QSjKp35Kli>s| z@!bf8(2!w0pK-}&tEY#MR#2BV`) z@JYi3+b9JxFZ*TyB}H6}ZdX1a<;hCT@m*X$+d%tL^hxpFy;KV>_#gE~7}ut*Jhb16 z$WwwOV9KbaBy(xCkT{bje}CZQWD4H)gpdDuWq&_WVjVfK48%=}y^_=QE;jF(L*PGv*_eX4K{ zq8(KtVCMe|sqlk#YUqwaNQDs;J9eLt>42-{JCg$JoJ!q_h7q>UW^?jDk^zaPG))Lp>=ORt(I@|03SgHm$%%H$c-{4m>)XBrQXB=9@Oi(;SXpF=C#D zTf}$qXo#5a-AT^8eJ{=`c*1#WqTf@sV!5Ld71x+~E0z{>6WP0gs&wLtLqrgDWXW8m zI%VMX(*J9HSn2HVJze?&jjydE+qnF#mShqEoCWP7;kdw`2l+9)HFA$e)d|*WY{G?Y z2CD5)yRFDhU$lr~=wlfbpqdJ(lB@m@f>IjMO-@;cG^kQ6_}yEvqBai?$g$C59n8M| zQ0lzq**=m0$wJA+WRZxZx`2BRsNlr{z70^C=95^P+%=@{C4_6P>c9 z5Lsari)$AHJ|3V|2gd)(Poh@yj-N5*`4X1x_=L%3O_&>YmHpc#$o9Z z8mT0!Gl_-xlKANhT>S8glRb0P$6Wu>-#QDQM-+@)$%5K_ik*_`Z}mj&Fl~OZh4?bq zhj!c3itrIzE@y}2s5Q9S3p7|x0wPqBi3)yeE~d&i^xQ3reCXl$7yl4sZ|cMG{|6uc z2fZtV40!w3W4E;_w{Du+GJHQ{PpQ+i4WM3xnV|hHWrtusH;n!PsB?*2ILx~^`ra^f4AE)mIaf=H@pY4}_i}+Bf4Jr# z6seegSica-7W3Nw`HSHKoR+64!z9`TE46-z>$)Se;}V`QUh-jYcUNTts*pK*Kqr&| zy}l2B7y~}%Tqk_mM6*Z&oG;6mpmVOFlXStuf+WRITidyeo8?qjAJPHF4|x^PpokAi z=yUFpmr~NK(;NVc&9Wr#qvl$3Sux(GO7fpyer+_xRed?IV@lAJ z8d!c0^|MVE;<{@K>r#&yi2s32nppLGq^zN#hQMq^UjZl_;~ok;CBz#q%Z$Q$b$gx0;HZ^URrzXDQFZFR*WO)J=ql% z6`NZ}6LxOL_BC+pqIj$&Y4QH8jj_<9S(;l9Rv#(T0x8H*Z zNTakgN=S!v2}pN$cMRQ)lz=eO-QC^YN=P$wN)Fx4**w2^&w0-u;xHE%!`^G{J3se# z6=}SS;g0FeRi}0$$jALYfjcsbSzzs9EZtt!dRnYV$8b56oV$cD7fyINAvgV(!m5m= zoXuyRK6r$P0E`svnvh(a{;|GehU8O1tYtzwf*CXNDf}<9D!BeFzTx86Nl5mg90d}l z$g`u0bRV}_L<}v^atns*F0fp|1$DEvNA73t2V5f_F_EPP)@id-!hfGX%t-W>{8PDS zdhabjy1dLI$r>-k!okttnF)dB7Zw&CZ0=8R7##!z1kCVovhnf`W6ASX^QtXj4;nJ>NMw(0{z#N+(k>!^7!W;Wc{ z-u|b&-`!N{IU)wh-%ZlzCQ6XHIv(&-ja${%hl_)u0vFk60|hu0I?ayp>w64#9@72Q z)YR0KtSV@zs46p+Nf}m_g#`s1_<1RkRI%$1x96tE%2IDLm*!U+jQ-!gOG+Syg|rZp zeLtd0!<_boJIhWjpoacq{|c9c>1%H3_Qy84@M;eo>00{1kYADgr72Z!g1ZjI;CnEy zgqqNBq`NlW$;bf*bK@8%L9*~qzc?ZcRFv_Xk>?hQRa?1+=ZaBVr^cv_s8sV=xoT_b zSl>L*d&(vxp8XsNsEtA}E#_;oS)hrh6Xpp#^JH1p10}H?{$%*Vh}cY2!1=~Ux9IJx zjMC*h@FtU9pLyNS?+pqcpi)KOAfJ)AiSwd}jh_1Id0S6p5R@Y8S#jDu!WWNcA*FULGRIZ@aq22*~LY5n))3Q6&00QJscby&R}L* z+Ft-2D?Lw7Pfz3XsM(mi+=UW*0pLwxhNqQFM{aIls$Iu?%~ivqZE2GpK<4xT^zY%! zZ6G3s;~=q{N|`CJZlR>UO}3!i%S0yqZSB>&*?n(6KfxE!oA$l4?|JI#$;-S-={ZEt zi^1+Zs`<6(=b@{hjLD7*JfFKLCwwb^4B7WE5hrle-wxLD150D#~ydhYA+ z9T)jbnx6Ds$!z8~8+e^fJe_{ezDF(4ikA9RG&z_LA3hM;T7y94795`n+aIqM>1ILr z0|+Rj!b(Vn;fW@e~-XDB74yB_JZIE2|VoxvSM1RjAMS{rh(b)P(oWb5Ku5 zr|iztmI^mQ6F8B(;4C3=@eMW)wl>hy6#b1DApa`WEj|-Y0EjR4zWpZ#!SqG>wS2}} zW7h)D_O6WK3bx$86({^{QYt(h^;o;!NP;!$2zDKxJqK!BQX;R-k$OC&a4d*6dE2@a7N^eL%1XH=1(RW7B(w4kP^ zLtr`^3p?Ej+o+H{+CPe8gV)h-E>tXv zv7)+K)C5gQ7ricxy-K!#aerJCr1%Npk6{5uwUrWodmr*N1xjS^g=E%Zv`#n7%JVt*IcL&fGEk(ce9{7&) z^y6v38Fjj!QUDmtulN%LG^G4mnSGWB-WuW4c{qo}mgCyFh&kc5<2&2}D{%Fs z8B==bo|3MRpjj78D`EZX{h=}v!mM(XU_5p{+j3$P%5Or`9k6ly)82t9_d?Sas4nYD zP6^f8bq$8DM1w?s4E1a#?-oDxkx{lyfB%|Y7%pV7xGCQ7+4mRy1|4p474Pi8Cu0>Y zZL#3{q3S9H5ABXBm|WEc

l7sp&Vk$nHDl$!R*)B7~?2dj|*f_v7w-wwl^<`kxpq zoup#^ag4&Eu5)CR3|IesLV*`S1#F$n`r372qNcq>1jQL-^>}k8HmqoPL62*$M%!$8 zD(E;2-&V;?%?y3tE393up^Lq7yNd0XlbKhG&5|$;p!o44{)a-bDwayG28$SXqM;`~ zF08rx{bq1vY6DvC#MCQM85&wMk~Shrk^3 zJCg7290UO_$lkew775Mj1 zE!lD&SW}L2Om3jUwRH^O)CaRH7f6;eh#A^etS}bLT3QD9=rZvKsz{?aUw$^-m8kxn zN)cO5tUyVgXZTe+YjD8{2`|EZghKtmC4(efEW0&qfYQK^TwXf+*Hi_MU?R#n^K9Rh z7zzqAtMerYip7G5OAApLg_-%Xk#E@xI^{ZTs-La9v=Ac9PDn^7!=w2J{-_%M4$RgB zCDQx&_{^aiyZD-z1j$g=TV>a}E{fps>eJgp@GgA6OX;8*jfOl$8nlJajyG z@w$wlM#+P}yecj9=3P;j);D?+4`UT z^eN0Gy6bss#f#wmd#&{6O~Jbl=tNu!SEtu2UQCG)O90DzPIyAr^7j(F{KTl=(N^%> zN45bpx1laLlt~%TpQu^G3*ZB(w6<}_5b=@2uZXBew{9BJ&BCu31^dC0xJPgyH z(vQ8V5wC#j@&UkPg7+j1dGPKh*`XZX39BAE={SPJ82lIGA!BFhZY!FXwGZO}#Jye% z%x|tJp4PT$>Vt9Dh}{6;pW27=P|}r?`O1RTvi8j=UM>~W10WPilE%Hn@Vj3mY`}7B zdpuNa!~!Pk8aZvKSAhT2m*il)@1w=l8gX8j@e*5V5|6)c8Os(c+73Z>n-ctYz=v%# zY(yV>oAV}X~zwKmm ze7Zfmwo@_B63a}VgzD;gtT&u1_Hg{F71I^sotj>~Xq@BPgL5+%0Ci8F>+<9Az-f$y zr^S_GGXz>$*w}bBvjM%VuN&jPCi(y!=y& z83Y1-rHBUBHP>!?F7tTo%c-N0r&573Jk1Sz04|Gr3YkZg{uS96Z+q7lp}4$ne1 zcom1rRO0M7Ul(90l8laxjJy?!&a^|G@gW1U2oJV2dPR`mwK;(`5yFQC9*iWYiv?oF zhB>DYZ!QXiW|be_ti_}BzJg6UYe?VD_AaZD+=`EMxC28Oax;Z#UL(P^@UHn|Y`w`< z;%1(*Z#onBX_!Kz!3J&$q;dOh!x80?cLvDdFybn9eFLQ%{yqs54`6x~AbZSI2)E^6 z;Hkqt*im8&6N+VulBJ_K5_MHditQqF9gt$&DudN%8KWF-L#ZrVg@dm0w5(o!WM3^I z*WFegUY)lV!pQXSr<4JF$S&(`79FSbF~0l?Za*(yqszAE!c0Vl7Rlvfa$X{i86!%B zwHb|D^><>4#Rd&GcBfcNThNFU{=mY{G_=onK*22fYaqm9Vdq11rn#$??&9xxP5znQ zCHk_(XS>%Z`IeikS7Jk|u^ozpJx2erCPAwlfD?YxBOMbR{Z`;M^9c*D)Z%Hl{aTCU zc!j4f3r$(=7BCaK5FmvR^jYfpJ!_St50iF`~R^PL4wTC($o0~eklC0 z$R=tQl4TK9OD%;m+ZMB)XDV+-_ohtir&8-Wfsl_&R|w^|ArI`N9{ zc3PQG#w0aa%kQK)I$9iGJ7S8>bG0!Q>hi?KVw~cWx6GKA`mK&ODb949SL_|c&I{&ohiZO`v z_Li<@60;AGkdTD9tky?PV}NaJv>hH@AP&ne5LKf4P%!_%`IulQ5AaAq9DLv(je$3u zaO+{f{7+oKL${Rjv|!x~Jau&Yq`~;_ZZ(s$Ve#^r& z0qIopW5XhC)Z^v-@y?*&)9L=hVdL_^VdJWvqTe$BaOb+*E!wt5Le$1rpCj!~fX}fA zymG1Z0rgjRo_4|UJ>6_t-$B|!Anivk33Zhoqt@;|@C;pW09$Shy=+_=g6cot4c*!K z#txErq55mvwa0U+OuVFxe?uwDDIWtd&U#6o>^JhlMgPMBxIF0s7W`$9xngqOhQoJa zs)zG_k-$kE>=urTg00ZkV8LO}^eNnfnm`?@dJP{T8XmrH1{|xABUx0|U}EzIH-d{r zvu6GmJ6R_6wtbG)qrucRP4DOW>;koz5w(*h@+>mNxtk>s@{ykyDgidMVy*?>6v<-) zY_=X7Yl4=?H$pUIsKsy5-qd9k#1=JoFMvbY&n2Ykf_SU@!|U>tllouRIz$xH(B(}L zF1$69!3su#uF^$wjM&0Wr3J~}yEf@yq6M%T7JE9XYSR7a4RG{QtiUuWWWg(hD3$0i zj@Z+E3@`ekU) z@dajzJFVG#<)Co~q7Wy02hel363+l1kMSQbgr=3;NU zA`Y3^eTiCFp#aFD2iEO5(o9hE==A;_!N&m9hUMM8I|s{_yst@%`V8 z@vVv)$Oy3S@4nX)mmCLN0>wtDhCeK|1pKfZnUx*`@Re8#d{u(4%Slwa;hJb%uM7%| zB00rizoPD91T3PT`vVdOxpL{HtN8GkkvR)@ik$?2+#$q~BRa@acu0%C1+@M{G*(&w z@l+{-zfd|g51nN8nqj2Z8+EJR*t4xF4YrW@O!Sw!oluejhY|-b2X^0P(NBy8PiBIt zVJRx+cA;GhA=6rI>F6Odb#398q|mMM`s#;r>eztW^j0m+f3HqZBEA6i1;Y9P$&GHc zy45Mqx=Epc+UeTua=9ti|0)t*eT?8B-2U||qN87rYCQ0a^B2XI%PXoIopHQrM50&^ z5OT_AmRzCm=vUj5NgTI-Ik(j66W%qOO=)X)tozH6z7}ym)8iZVVBHD%O;2wFYQu4w zKIsv2QfYT5_FT?OEZ>W8O(6Nn zYfY_83RR17FA9>u3-Qz#ipvFB?v_-mK!6;TM0cvnoDdhX~Eku3k} zBwXPNaXP!N_u%>|e~$4-xw>6{z-4@}a3-eaC0`2?XFRlJxc5G3m<;|HMwC{1#zX07 zUm*$obNnrq*t4A|a#n9v>&Y$jbhmAZ@R8 zAL=!Y2))^PZlC+=gtK~YKg_3dCPMuP2vR2m?s@$^m!8&@pSSAeU|LF0>T~7*MCk=D z{GV<0veSyD5yoe-IDA2RK0mALO~O-TyOm?zkxA0T(SO>a#Ma}G@#ZV%a-`;dDHKrM z*Gn8OuTL!fN)vQ;l`TfjoBEMg5K)_5Ty&v|AiZb`ilZ>ZWR zE+yl2VZ@fiYc1h5PBOy9g``ui+qX`}rS0+9#Xx^6{&n%_zpCjd+3!t%N}2E5GTj*U zAkZ|z>Q!FOdM1x(IjS@0<}O~E0x6uHPpe^-d+tAq`K%lkP>g@HgmO0|m3Q5g*#6_IQyUlM$=!F} zc2%b?Fc+@@0BXOp@nV`oyx-|0*3i8U>9Q;-+V(iGk?33gl31Wh7d+fV{cS!GpW|DA zu5hyQSTwvzO{`qL@>@}QWGSRtXYw7t(fZOUFW@mOCNgP#M+>EnJ*mfgZx?gc>Wua@ zX+3iY8RnYT)XV%OM1di$y{3aT8TZbEi#|KT3OgcfhxOr zg*P)knDGu>{Ykdc4e_p?bk3KC=LaI`g!3KTR{SJ|dg_r}zf#7c<*CTm;HMBsIGt|{ zSx}@|erfBAF($&b5^f@hLT~gXr;Da_HC}UyjtO~u#Ct4gpyaQIT9w+#8tDH zZ$rpdslZ(=j?^QafD3+FAqfYy9e%OMwG}{1Y^-loOzwT_4kG=^kLlREMZ2nfPT(`y zlwwv&gxm|gf_8GcSSf$0-=dGRBCru=Ka6=q~3cP^iQc zT$rFqml1d_%eus{b#Z0#sZfyg-rK%oz^P)VQKh}!`w$+~wSa=8gonH411=+oOG(C5 zjr_XD{>t4s5v%?S;SaU_TiaNfpv$U`jP@^9;F((V|MjeT#eC+FF%7hNSA(mh{iU$X zq&AX{qV@3;HV$&`+X7F+^WW`ag4 zZlW=Z!5%;%zZG{vfMSYM96Qx5Ia};U~y_uJ4{N{zVJph3I*k4HN!GWh<1O1dT({S5-WV04U?S~%EV|f zCBg>Cekse&Swz8>u4s`EhIA)!(9Ez3FnqS8YgZa9{^Y~DAoXq9DAr1I1i+&L?J}m0 z30lATl`Bfu;z#us`qn3y&5Sq~Y4z2djC%l(%W0YI>C6ufeeL3{>AVb*6}U_Kt*eA= z<4=f!^CDtTeI(j~->O7k6085qCLT!Ea4_%S8D0$8Cf3{o^|)4`=pUr{z4wMkIZm|( z{uj>dQ>7T&55)-@&^_32xGBl!Nyj)gcfXHWmZ(5-C@2NuORe;?Dv(x~9_f~gD-G!F zuM{h{Zk#R@E1h!D{tav(kr}9yq>c7B$aDClglg2JT_u{E*Ld&Q9(0<5>A)iijPs1F zL*H}S=X1D^5{)redHBrr6JJhdjiQi*${{VGMb&qe^8@1sbsYG>0bFRkXdIh$2|u`~ zc`sIFV10RV>{j&$K7LM|1?l)|4RqD1YDuv_*deYp&@u$go<|_vj8wk2j!BWWjvWq$ zw_qXDpDw0q?e>1(;VUNJI_iyZBv@LwY(`#dc62j9QoIx3)T$e7#)1OI0Jw^j{<0*V zmm00=|Gsa!J%$!^pQ&(4G|Mkh5#6Pp@z9tL36Ic44-KMf^QV@9er$lRhGj12natxr zk*9s@`kJB5RPg{oE=-Ohmpec`Q}5rhwORp(=g^2MehOD>iJ`>$NwZ&vT8MQ9uki=! zf(5qDRmqB@#Q}>{50OJO-la9v->ML0a{4p;rJneX4QTABo8xO+OQ0&LN_>*oK2I_q zJCKRs2gBJ&HFj8h4iOsi!AxBhTb8|AXkT;PRTF3x0x%*)PdMiEZxi|ZcgZT7ks{Pu zYY8M=6D5M1f`n6zjUL%d?)6WFxh;pXA1u#%{F)F}+y%be#CSD6?4s>5qQTvwUBg7x7_G|6TyJ~H0@ z-f;I~@2PJSiMU@g%n8L)S9R+1w}9ORYj;Y;R{aY%#_q2<&FrvkTbR!GfC?R+6~x6* z?|Q}7Qx`FtH>*;sw7v}mg@>eZo+xY=!n9kX2I+?MGRY1673Lva!&!X+zx;ck=iB2Z!{l zVq?g*ynhd^!xU#ufb)c?fzrHAdfuO?-eBq3MAe820TpdQD_atFe%LD_=i5@jf?2!l z!x%}C1@sVIKk-&+Xo*ry!f;qmpGxYHK8w`oSb2ez#{+DeD6ghW#a#$PEJgeYeKso7 z5U8v^2DSC_p7CJzxYhAKU+7D7_jX_~y-5P>_k3JMF}jj`ocGICl~aX&gsyj8hEw-C z@e+S8jt|YA%??k5pju(a#kYYe*QbUga>j_*0@ zF)8%w)O{N(_LC>I4)`hByW3BN|K9F6P>`=eR;j%^MyMqGcJIQ*X#sXL@6x)KyWWyY z)wi>f;I|w=s2>-uuZm@l!jYKYZhh`0Yskoq+_R)CFD5`ztk+->PEWCEdt0uj_T%4y zLyt7VKOV*=-k9MoYf^9B0_6v#Q~?7XQN%u6;EaXq$l(MH&~Pk(TV9 zp9sf}vb&`RS!-PiEoZg5>aG$lC6ke(Znsyb@!;2^!j*P31<;E>DvlH|L6<#Zg}iQfZi$6{A(XDT=5 zWaV-z!Ue|)vLM04ap}3Njyj_7g8en{hqQWfsV$SS69JwEvbsL{cUBLy%{PxEiBeGR zM;J(o$^lur^y0T~gZHgeebZFStD3W$g4lR$-&Myb`Jl$#$T7aQ`abnr_4%`^}HLyl^=$hTNKS z?spy4zbgrILfChA?tquWqXaVZbji?~A-yuB zHT$omb4$g}G;~DayRo#q@#v<(B8EP!JChXjN7)zIfxv5Ldj~s8iS~OMK8`jvYLxOS zqqu#Hy=%|<*TusTyot>9MsYPUWcA9Ha)?sw%{B{v6+p?nn#vL4jS&)mtutYYO>?ZU z??q1jz@E%qwv?DIErg}qeQTl0RQ7u^v!bs}2rE%!ulJBf_+);#6-gg&W#_2dF4T1X zokLZfjlBHi{B)ZzZ#o@pK?+i{D@K5MMPDGuyU5zF9IT zFVK00nV;=V;`UNqPB`HPvbno&Nuo^KKe4uF3F2y0Wt8?z+bflaB~+P!S&3v9v!W_e z^g0XUQ6sTbRN9I6qRn^;PUd9ow!Afeu=BNdM}>_@jH=5UCs2Z!TfZe8eg61Pomv83 z7c(pi*j?Uwkd7L@#(;f+A1PxtfojvwDe~D=oc-?!T)*f(X1KOymlL1eo*g19Cg8wd78Sec4FN-x~x@$MhIv9f}03!H~wB@vU1bOS}g7=wF+VymVDz(&9O zmV@YI2)kWK3l&M9dlg!RCa=yR0UtOHiA)9?%YlWg@o3G((X?ff%1wVFBV^x`S@8t$ zw2C@SNiUI^HW2rxIT`EOI4T{={WG}quPf5~aZn{BrFHQClo-5X=);XTP)=$0K*>Mq zah((J7S>Mv`+I$gHbKmoeHZhFmbhjihV-*1rsW&wfy2RPAzh`~yABSoyoY%%X%~Z> z2TPT5Q_{Q}&`_uP3~?os4Y=jGlKq8+8uicJ=~5af;0dElc~xuaHy!X{wcyq;x*XrP zy?qm0A5d;HaitWanSDiBdCGNzM?Q(pz>-d}<*q z@Db|^=JyHXkMX1XPeM>d{r^?sB`7z%H9#Z7srmY0+p(tH2E*Ysb%Me={w^Kn* zLG=H%YhNtnTq{1pYmv*;@RS*~FrgyRH=q#3v#!*pSPUdc{aiCboqrq9*(KzaV?#zi%FZ6P9 zYN~dnAMY)Z6z}aRxI0 z(Nnz6oBn-oH#g2>k1;RW{lUS(=I5t-=&aU+yo}7tFu9LQM`>xqiy*A}9v=xtvrg3g zQLEi$10WgX0Q8Pjh`jzcba~SN&~T5Bk1rywMMa%J?<(_dx)26vX#G8EJ+3Gse*b=B z#p_r%eYI@W#xW%=ZHbu_Jrq#wTv2j8C@%igaaCVg{wGv8JA47>(G#`Tz`&rZrlGRZ zP6R|plV7!XfRnh0`oFTa>0pp6?4tJ%;g56ETS2i%;jq-zA5ziV4#l+j8v}Up`U zFO0;%mV8eh`$CKGo4yRg_xIMt>%TdA-#N&t3r)WF9E#p*8)#;48!=}D-M&rA47ETZ zIu61j|BhFmZPrdeYs_z0jGG~Wjh;c4>TsxMH7ysz@TI|@ExO0>`sca3hFqe&;}A`7 zjZs(lpdvY`bA$21B<9%{8vW)`k}q>;A>Yyn57^PE?Bt@)c)EAuUKiuhK^OKxT~N3L z*ES+xI~sln_~P$#e-+v%=P-Uaq&i(zp#~|-Y zHHg6it6v0zzmCUmtqb<3?fg%vvp^>J=*U(M5b{mzd@zNPOXKPm7dVTq*`&>{O1xrE zOuV%Fj;H4y@FGN4nqmb;p>uHAANmN(#KtKy8W>X{$W7m zE*NcL6o78U#Kbt3Ru&etX82fnc!q%HT@}yqr6*mAxR|&&=ZN~$s~?e(AZC8{SZAKm z+w&c|6+uD4PRhffe;`Yjd8np_Mp4mfS$a~^np5U|+E#U?PP39)rd(mArw;-m;_Y~- zfQrMxs7{CXe2uS#MNvgHbVgoIPED5ynw*kSQ&z4n$j;vXBB!m6n|Ee!_UEjoG2(w( zF)#isi2rxaXb3kyTH>E$n~3&H&>8AKwARM2{7;OshKz|L@?o$4I7@x`0O#} zzh7d+D_E2k7)NHr`1kaL8ez`t)OPTuo`t*!U-qbCgsg@gNu_Nu!~^CfAOJ;iOC@v2 zIGI;c)eDn|uIvq{cx1H+(H3G$X+k}=wPe;%TYok1{89(43~Gg|m`fB&jD9SEsw?F! z2p9dW%lG71yA;ZjS(uZCX|xokk-1xdc0)l2YwxnemNQ#UA9=LV zMtR{C&oQ1)FiOwGqlnf6NguK(54*a)h=TH~pC87ay#vkK9rk*HQA(fPTwT@JopjpV zPicFV`8_*V^(V#+S4~zb3d-|WZAKO(--UfuJs-Td7qv11SE*%1~8$M*aRf z;MxiZV5&w^re3nKu_avg_V&6YQ*ba@pKr$g{s`c?IHZ1n2JkQf*t0IHk@p3Y6e29x z*OUkN-h`KL3csp)`9PG1mhH1lj6wANR#wcw^ptth!wY`A-o2 zpN3t~>Z=6sW$fdl_9vo!(7xkH)ML_b8XYa0C?Tu#x5$kF1XlssmDHclEz?os_02<+ z{A;C9>ZHE57g@ZDCv3m-uqg>Jc)fKIU>T@_Fm^zZS7U;^UCHsad>q(D4CDI&uahjP zx0mQgWD+3iLN26VDFaXv>G%?Hr@OHh@MjLDi=dVHbL;(W58gAbuG$pu^XGO7EmCJH zK@2SqcbBA0mb?qh{K(tGe9sEh4PE3mu?{2E(rYY2pMdGbj;czW+NnrQ`z$k*qV>{B z6Mf2qkSEO73x-^YT>-H|hyhzcUQk*4*{BEFKjXxo zq?=bc?NIMX1y_vFiN{7DL1_&waqt#wxT4r!!ip@mGXO=Z*>?%({LcKr0x{rc(jx?j}p+U`5|6u{F*_2Zc)J(0Y>*e@>2&_K7xcCRLxvTk3 zX1UE_9+jNQ@7Z{+D9Yg$5OIT+Rq;$>%Ce2#avPF=6L@D{(3cFU#vul#+tx>4RlXMX z;l#@q2KL=+fwAjhr!oFU$0vZ@y}c+DY~OC6SC(?vo1|Rvxn7PxAA&DQkd>2je7M;k zyY}qSil?RQj-QFyCs-|NhJdkz-;nole8kBM!USIZ>x=(SOCy9=U$3sG{Y)FRL!+ds z;+hvI+B5r5Zu;z{*~43JkCxRGAQmzD@QFz=6og?QVIszsQ6xnZyV4OF<<)nQLxvjXQ3?&o;k!TM;|QyZmi>X@LQ`pS?k@%B z)+uSMGoxl&Un=#fQeh)cOx0dpD}8*Yi8Y6W5O{HQmC)v!U)^nR65c#GFu>)o(Koc0 z&g0 z63^Xi_C&nZ1kM%rz!%+DxhJqn(dm_ z5jt*1?GlIxBgH&U`|%(_UVsOI1SQQvq0r6SolHb$i`}*EKswlBdoCT;ES0uSw-pcb z(QEg|t^O6?d(et+YlHnJAcM>8bLT8;EQFXvtLpfvzTpx|XAXGp{QL!NuUWQ^WG570 z?KU=LUn%`}6)}yprGVgD4!Sm8qf+9?{;84hRd;-B!eaINkf8!()$GYq@&XxP2*rbv zJG~_*uC|IH)7%Z}>WFo5KPbTJo0z2xgmqLpOOCz zGf(Tgdrx1jU$g&)1~+glKmA!nkVJHL=CJi`Y&|`^Q`=@(t*PXD zyWR<63HrG^-;$X$oBc2-=-#slpw$6^VV!30>!al*`(8BDN`0#bAS!SXee(u5!fmtd z;cS?$(5`t47YGD9YMj84kq)bR$DPjtFTMc?R~WfDyGkoNh5#i_^se^nm0?Kd z(`AiQ=hcGs!y2NX2Dc9ocAiAqdFLM7K=l360piDI>!KWhfQ}zmj-$tRG<9@zuo7<9 z0x@ROR+^p6`xTUU()F-Bkr4vv4hv^P%S*z(Qhd#wi1(kqgNji^(`o&A`OYC)!er~= z^z<~m+$DVQ)ypJ{2}<^5qoK1i_BeSFu(xsx7B9C`?aqLIv!8L-fSH#x9+#4JVnhG zMUgY~Cn^8!i|1sIT>f=Ko#`14Olkq=3&&ShIqm#O8JJ~#0(`$woyCKC#~F@mJb_>T zTqvm-q(XOV$MOI9jypOz)7|1QTmJ{oOhg2PZJ>=#9-OZGuVohoV@4_jw1lHmVz! z)vD9(tKC+0l?&Q4PG<%>fMiC8Hsu}|P0H;Q+FbQH<_G4J>UgeZwfBzopS7KhHzDBm z%UNxLBIawaI0*w>!hS+&Tz)Bwe# zdOEFQUo~tfkQ#1|OmW(1!nD_HScp-y!ritv!qCO=W7kmMm#wbESqQj!xD4-PtGY(B ztPLgJZB5F|l1;XTCMU#U%f;KWYLIOETU+ND$iBG?E}V~cF^YGG+$6;Wn;v_0M}5f| zk9J2?b89ee(sH|6li9fR*s~sgWXE31zPqE@*iXcexd1e>t+s=dLd8)Qel01hlFdU5 zLq!wIG2ADT@g4S4KAG~(?KsRz7Mi|WNFGDOmBR`QNn%7GBO#|;Y zosG?p=Q~cn-XO2b$id5eFzJ0ahJCAaCyR&2@*JrOK8nu7@B<=PQ1AR^Fw;F}V{QW@ zHF4+4ozJB_f9dAZN${x;3uh-ohw~}SYBNG0&3AK@lP)SeONMrQ@^IEi* zr&c=g*OnvY;Hy64>YBu`!@|zaOgKdJxb}x!ryVt4f#bPq<1LF-N8?X-nk)LI56v!{ zbfbP1m|EqgHpQntI0G0M7|IXYM&kPV{mr3cnV~tWbTb2)f_@oWtF-a6u=YUIZ0lCTM0 zzHa*c(|t2A1_6W|H=E#dsfin4el>GU?fr8f79FX#@1wQ;W^Lx9jjS>3ONqllKll_l z66ZA&9@y_~FEO1A24VcbefVxf8^R(Q$0M6g(fxBMS zcRhNs%S;_N8~ZnvzVX1{mvsP`XYZIyyaB( zhXR+dUtH*(4P1iA(J;vAOXvoq@sFl!31?UAeJdBSeL|ae@^Fp4akN_aG=gV`CIOuF z0ur%0!fkp&FxD@8TuW8&hfLeR0wTStd*_opZvls8beFl`rkYL2&_5a+6}#$*Ob)t< z;&yauZu<^@Po2#rnjecy-Zh#=t4M`@O{vQU2#X6u-d>+@9_DS>lN97Dz|E1PxsM5!WAdHZYDni@F^bvNI-#`-d6Mwl3b! zo*L(_q6B0kmhsh_oa!MI5;#ZhUpSA%Yc+vr#6PvecPkHZotwyU8J5k);4a`50vMSO zevUVq!c z@+F8;rBXyo z3RA)FGrP*|15lt5i2K&v2pkV$)WfvNq-Ie*q~8CF-wYVQ^OET+jkDi{yiqN~wo=va4m zW7JJn@(dH=g~{GLedp?V?`nMIS#2h^UrDAaD~`DRgf7G0czPT*hCz;@#@OKM(=G6$ z!3SSiu`KNTuKJy$P^)(1A|1}p1ss1^!N1;fx}dt?+`r=Hvq4P|`{t8t3WrhzB};8Xvje2HI6f=`pF1lbPbc=lRDot7v;+ zYMcM;ZxE)TP3_at(m?x?KZP0jxeQrFH;s|lK$~MaYJZf2l1$W&)FU-rCfPsk-}lZY z36RtMpU}MD%-kF}iLLzh!E<}=7a&1b8VEaacF03$_*+3Ej7vtwu83BVl1?0zCw+~k zr0%b?5jP}b;0OV`>B4f$9_tq`OFTsg+9ZKQp-UBQe2DXVb=t6aIp}_oC7w2*5#G|J z&Y%+jb8$=#oe$vg(hSXg@13dd#7e;YZOyWjWKC+T%XEsoSP8aR1wDpaqVG2k&UrQ_ zZHiDliUcf6um3#uSEaRTbqtB%sip^XRJWfhw_1|cBZLNX72i?xu-X#fyD_UDgQcoS z@YK{X+iaN~KdP#c>ZW}{7HU3NqotLE=ys&1k{tK!I2v_+mNaq3E?fm$+XLdIhfcteLEMQbo;JiJsPGQ8)Rp%7~!ZSBOEjX@#2ZVP5ORuX2YcB z*ZbgsJAd_K|6nnNU5Cy{GLD%3zQsSz6r0uq2dU8IOGVtqzI-&-*95ZNP=hxV>jP!% zF$i=~GjCsI64s-wu&uJ{F&K?Bpd1f;J%}!cx z;W($G55yrUN&f2kv*g8Neh%#P?B3|Uw1%Hva@3UB?I2>`o1%Uf;YYcq3OFMIuEmY| zi`%uvYY}>FpBK4Q&?G6p03y+0U~ap85!S~1PZj>x1b<^}_FcUG2H^0WBmL6%S z`5$&)hLxU2$7?b^Z-vZjJ3-Z3p232(tLNF9`Z#jfm(Tn6Ggr+(Acr;enY^Ly*3~Zg zN5##Q4Jvi+uQhDi__p83{Es^xZTp z-pYzE>@%hOrbzFdmg<!0I1v?gTaDO>$7_D5 z-JztR3>sfp_G}&BSbal|=j^%mz;QELN0-%$G6t@5CFX@YDfY#$SQiM(Gjy-!hQ4W9 zyAqfq{bqsiM|EEQv#!sG7+OQO-O-G`-BEy_fW9Fy0Wl*tB(GB!;o+p;hk3k!Zbb#< zqi%RNhTO|C9EaKw&63Ant`~7o6CE@;GCUtU+&Bc^+vPsU-IV*Bl=E5rOi*P_(q>NbyAxF zCvUstfq2>A-T!Sg7nQU=mC2}u=5i4Jv`X+-?sPb)*?Z;%F{e($7Mmu2Hi?{Z+nD^+ zF8ZMhKVcY+5l<}(&KCbGcZEp56SIS)-){T-(ElOpEra6RnziBJ?t$Q%K!Ow82A2># zxVyW%YjAgWcXtmC!5N&Og9R8|-bwaz&UyCttsi&IR839YYpwRax?2$pTM+++IqGMM zwqfFt;I`g3tTH!Lxp_2ebZkh)!qxH;JfwK1fcZ42o0L8VXW>v-WQFUleOtr2VQB&F z@z&tS4d8u4&`=F41N^MQXbdX#WAnXpQuz zY)W@$cC$xX|Pn~Rwv@7DQwTU)5g0$(gr`0hxNAeO)TXTvy z7@ciz1ABbP03C?8=(vmDwjUc4&2@sy)Zj@4&|aOoFS;E1V?r|;YBVx22F_p9UZ455 zY^~WV-0)uR12&oi-SB)oglvIAlof$xO+nvqa9=`fp#P;DPA887zza_4vl`P!uoA)C zQK-w``=xB0$j6+H8Q|!lLdf7dRQH{Dh+Eg@j9BqLY)UbqOUp#+wXLb~^TWEr>MvE% z?~xFpe1!`v_3zp`7o8LN^so!tjL=ntbAevtK?g zx=XK&wq4zzZMZDP3HssdG>!8`Q5;mUYz+DaUn9{OP#NgF(G9!#s0_aNDZW+*^Kvaq zGN>-8vN=-2IPkg@L@pod$u2*;9g^GOkZZtFG@wycT|95K-ROhLSa|)c$WVzZ%Xt8R zC<49H)WR6QOpP9Yti+qL5ZRU^>k=4D$m~ew}<;W8vH_uxQi-x6jH1B7%u2VIi zg!{OJi5zQ1mBBl!l4ZlCr@YNmbyuC zYR+vtnl=8?3e4(CLnPs^7Xn`B5B1F4NF*e7x9bnLy+B*#%zDO9p6zU*=cW;qnkZdv z6Yf^n3kc5mWpwzoXS`s5F$aityQsEudIJ3fws&h9)Zi?iE2!A?+RLq$XUnN1_DPrP z_bRW0D!YIGbdryr(rH&$8{H2muPPz%aV8*jS5Xy2<;lS5FCP*{_Hlz4O;BYf%H`!I zEN}unr7bF&(pAl$Jua;(R10(u_?%U2tD1=uSJ5fWpZOurqkXu34$Ab!42a1A^)DW? z{#1@yDGF^#xw?wy$w)-Msv=i%6+61*aOw(FmD>2U*FuMT*Rlt zcY1pF;F551LJ8nS8zB3_Y*DeCm8%si&1N;GMh&BrgFaJc7J<+V8`LBab87lGeAES)_&_HyT4 z>SE`CF17Nd=pX)ABnk+Bj&)Gn`^XQFek@-Ch&L@B%g8m|xAX|Kne#CfxPG|CQmUhU z_$3b^jddZj}>Iu~^w`gY&-jXdpS9 zDe5ZOUAT3%u?I!p-Sz88?pOrQIIyQ<>9bn5ax#dJ8TUuYt(>sAJ|XhJHI zz$S*=o+1y3okP~wCO{W0oZf6q(dHGR1kV7>QL7wIo0L=Z`#Yf|n#b_oQs6(fn`jKARIfELNqqovpgXvj68SZYb`{fb7 z+QaOj#_32Vw6*#rxdgtGXIEigrR9Bk2;A3r+0cCP{INT$2@@!xYUX&%kg&AfA|(|y zYIMCjP~EfXGd^gN=4`6Jh}f3%B?6!Y* z`F!42Kl zCR6i0kF_2HeQ#NKlYX(d{Yu_CoHqc`v}MwqD^c5BnmX{huJLTWiFqb|9` z&8wOxkgl}DjL-a4!}S9z=JIGhaup*TtF$QPug`0z!FkQYFIoHQ^#hsRt! zrPy5Q*8S7@OT%E5vhNEoFzu71{4@HYU(YM8+gjAe`$`PIUEHEoA~(%8DOmn9=d2?=3fpPZNQ+k>#C1Qq zTm?$@bdjBr(83mGE)2*CkZz=J^u2;;wpwmLoPCzR1^6+}+1g;wa@MNJG!b|$G?(P2 zK%aLe(IuZj!0i?c!QA1;;}~7P7Djeg8Qo{0=GDR8pWT>z9*CsNMKRdbLpj~3 zOq_Mo_Zygv9osQB{y-1QjwzIP;N9}HqP^P?C$8UdA`h=kcbhs3mX^f`E`5O=;OQHU zeg!Ihw@WH~ok~6%)*D!`N4EnBvDwmQiUm|z5BKa-j_U2{Jm~&J)^4@Dr_F~Ye|*Mw ze(=%4RbHSvSs?cN0;cE#5Mw(fVNw(4a7j6o=UO$U>mgm7>f)OFnWrM{jFi5Smmr`G zHnY0EXNjgfW~DOAf8kueMb$S<~EN*_ zimI%qobMOEp2v0P&~}Nmc#J)RE{!8(ydr%Dx)M8W;Pzq-XF(dVl)JpmJ6af8EPriv z{B$@?_>c#`?#rveh6mHd2aH{BpDy-t3)PHouUU@TQNAF0<7>ydm3zjdP(~WJz;-FM zCO;*f8ef4bvIK@k6D!An0U>Du{IO-TNoG4>uk{iXXVP4W2&3d47>Y8gHjcxy4pr;> zQDBZiaIR)kj|3IkgJ)Am#*9qp?^{>q9yW=SyK!dKYhI&!*X^k{%Szy!-BIGZfQQG$ zNV~U!JP6;o)ucf=_TvX19C`Q_4(1s0e+ILF=xz!fF^^|)2gM1WRxcE#ZO3t2;@d9I z)!{_iHInu|df$srzQ4Ad=y{g!soAdw-A-xfbIdNQ*k`Cqa6>$%UZJ~P->N``X}&gR z&_A)49m2m(;c^)3)y28a(yPFH8~b*NhS#n2bJL>Vyvko=h0_;o*+p{VH(pm&fv!CI zdLRALp0x;j;oDWv0&~iowM?3n{>K_cSOw3{YpOSuXKst#Vc7QLm|ll^3`776QXcQc z?otHSb#M!(LbsVV0?4vwg~~K&CF7?Tss0BGkcGkND)SEc>UE^WN#4R%-d9rL=;IU0 z_P(lPJLV#=&fM)6Pb;Rnwq+5B4H!}2!4OmEwC86ymn5P{1^H2`26}mvsMAMt1M^9R zn-A7vd-W+J*XgTTTWl7Hl4APZqqhr}ryIEQuVhh57*y6`A4+EXL7#HIArzHYS+bSG zeATS0F7R$A9C9f)Yho=OPyi0e3;NofH-nsmTfQi_<@vq5ED*+yrS36VCiZb?N8JZN`w#PdM(OT3Iqe|{O>5(5o$7D6~%8jKAA-^rJDV%H1 zmuZ)d9jX^fUl{*PK%!HYG+qoub$0Ll?*IMB59IK*%S^mSR_;J3Z-m?W;Yo_&HdFTJ zGv1hrDM}?I1_&DfNhe)67wl8n8Q|mL)xN1Hz-c4+SmOlJ9g%@V{Lf^ff5# z+~_zdV=)Xu;B#Sj4+Yau|68x9I(lqzVQAbtyjAJasLuA10N6|&NZ3Or}o6y+^qHN73jJ#q)W}RXU(3uGS zCz|8s@TgNm)@0z(y-a0X!d{>P(fnf9yMgY|p|8O?3_>aBX61bN=Gt9!NppFdt!NXp zeKSt&bql4RohO!-{0VFGb_Qb2E~dxy!a5a=blj1y)(xYwH0P@ea7bTh*F4EG-N5tMTX6_^pn=4c*{=UAIzdwn#VKM&!^&s zN4G3vr%Ka^5RR@}dD`w*bosFfZehM!%!THo>Mn+ab~VrZ;ZDlz$7CjS08K`z^`e_) zfC9~yljCX~<4V2SI>805jW;cnBT6t{jyp-@D*8fF(3=}rm=m4M-3i|p(v%L5ZP%VM zrr6m3gp}D6{^dM%XEJJM(P)a$wR&hA8-Mn&yk1sRb>&HOU6ps)9YfJR6D}%sN$kPN zB(-XYU?vb_Sj7KM`vIGRPayArzmtf4PREtKEV;qz$pw7K$`y}iA6y$n)n0+votqke)qiFQ*u)O33Mjz|2|%d z0w#^XJYsBVs~IfK)i^v{A2F;{!TuLOX|OqI)TFk!guHY4xX3E=5{C5o72E$K`#b*? z#K@?=e!jBFkW_3WyFF*imhcF*>Q9w@>!p1_`CV3KZhL3AqIB}2w_gTA%A|r8rR-M) zp^m(c#v6h$wKH(+wwmb^jq8p)xw95CMk*k~$IX{irKphrD4jaX?bYzA$7gxF#USQR z_2QVGwM@PFdL#5H#+hc!ezTtFp;#Q@jMSQ>D)49XABA;RfJz>eo$!j~3vRcQM~Gt& zrl$Bqg9e_LkNVTyDmD3RIT$xKb4?6a_j;Qzknemo?{2Jj-zXM*zsE0B?eILkg8 zpWl=J^&0*OW&!{lKQ(Gry*{iSSCQ@h=2mznDXi7T3ZqPet%0dcpZiId6>w!*8z6+g z9C6Hpcp$FVEqYpLgv~()GLOoFA~7JemXs-NTFq>)+OZ0Lq)re^L$~81Pnx$S=M-jx zmO4TfjY5}fYM;!W4sEhUtQZ+MnfS!j;jCPloaoQa4o4Pky#mPikZ>xc5BVxzmk!3WL+78)L(E%_|p!+Ts@>(Wf}SD;Y#`YsYZWLW!|Prx;ZU!A zLSm)wqP2=8buO-0?anljgW)>q?JnhC+(~!_=gnj@&?Sw>m0~oKM}>G$bR_fS%kAxP zOCY6NZIYZ;!^-|n#5o-iW)d``!3^|NO>2tNwg%c<(=a@_3vp`&-|a7r6p)kQLFix(tl61>5S_;j5qe!6i9zBA99IY%2(9d55dbHvyZz7Iw z$M?5kB0ifJ%BlPKo^alyW*zR7@#iR;bWE-nOlgMg3`JRR@bF22f&ohyJI!0A6lv0* z?%G1M-zXjuN4I`xe)QahQB0GD=hLxc&zmIGbJyM)&rjDDv>;NBlKK>^2$G66{^?O6 z#)DP{@5}U=D8sR=CU6-ea)so?^)tjhaVN3QQKoAY-=UZXv z)8f%>t&l>+&X@uUs4OX~o@b`olBH8aeNyUbRGDDu1QL_zTK!m-a$iv+qe;30_-9^2 zgU+cWS*VgRop$0i4fUlR;ZfiWW(2s(7wb-W`_)=TeP&pU7(T_LbMOI@NBjQQC2gku zSCYk=n?!a(-mmhKP46>_kH)~~-Xme|HNCQ=t2I0|{9m6QX87YYkc76c1#`QK%K?nz zl!vGZ;pw6kXtG9Njub7lFQ>@;W`*6ki9lt3hs&@O?Y2KvLuD zo3-Cx@Bs)t9u>zIu(fM^Kh(|jP=ZkYh6#c&C&?j~GT3DP3gxhQ=lz+Vze*?E3`>GG ze2nutb$zkjPKS)2A*givu(W!gJg9VYuoY0Qfk>et4HYtn)QwH{z?)U{YD?fJtUhdU zXujtKlQbq+UOM&7V=t%w=xrUiFJIBZD=W^WE$vjHy**+feB^T-pN`_jrG6l8iXSNg z@lEd(V`_7*aEnlkvA+BIdo7p4qgnrSFl1czP-rp}Yu&^Lu1=yP=iYp1D%dXX2ZJ6m zFF^YwAKrKF0;#8w`n<}A4VP;Tys`SQchjd={&c}(F1;Is)JX3Ijkj+=eI#n!Kx=iU zRO%z=zPBa(AxB~Hq|4ggHjmhPLLY1Qtso%|>Cb}F1i8}8Bp*!?7dGKUJT27R+#xZf zTJm|Y z=43tG*P+M&uFy&8lq}h>&|4qdnRb7tzwSG$;X!Quy!rGuD$bU4tm@rw7UNMY^J{fm z5IRNzq3iehRmA{RX;)3t|m5Z@l5p#8sUEcBrI&n~SHAE}xpOn27uWqYi4Qj<(VI{Cyfmii3 zFB(tLvuTFttM)8juR&J?eDGmQa%5+}otsMer?O0Zd zErzU%@OWOy!Bi+nRz@u35$Mrs%H?CFo#=I~XzkJ{I70#YdJH)jTMO1c(#U;@Mh1@7 z74-5P@5CjD8i&kSuTnpLW?!QjtMAK)ibGv~M^V}fMAsi#^{>Mp+~uOj8D9xRLr}58 zj{k6m5%V)bLwAZ6Pa^n%xzfc7g(VDckrO4B+%!G+?TrWR?fee{bdmP~Rfhm`OUr?V zn!qru4**te?|9G?rd?l}zM2MFukj4nz;9tp79en}$2ry!lwOhdc>?_%J~CruwYhzY zSc^6^$-bc(Lbw0(azFP@0uD2)B1@stqywI8lWXr5IXz=_bI@uB#uF5mtBc5^8m*42 zC-0q0uJ{16v%7I5j}sB?k$9J)?v{Z}$oU1-1PCFu%gJMM&H0MAmswJD&gzL&8+Xl} ze|Rfv;{05TyGF^87h;UF;@W(RvuLQx&BT<;o1)Lnx35nQPD>pO8zGPLD=NZnNHi(l zNey41$xr%jNWBQpGW|cWH-T0G( zpV1ZIN1XOia%UJR&S=SI#NhM7Z123d=eM&$7B6V$aruPv_2PVUX1CezkLA8pjUiwL zMy_VG?Shzyh!o9G;Vy`E_G!l=L1vNso~jk?h_jSuUeTS3g>;SKpD*FRe6ts;{6IWx zvcl4-N}8*G2W0UQ!;J|LYW)qc(#JSHIZUrJSFr>nX^Z7uDzuH`bv=B}=&53s_1}!y zb8S#U{0dHY&unBlpH7e(sZ(T;9MaR@9-B!VDQHpbV6`fZpnA_3Rr|#8E5tzDI#^2m zYmx8OAXNM##U{EVjz<=Vo3{@(q{d5R{x~()^8&FsH)kbbw?dy-1%`c6-r}sNkAm_G zlZh96u_dA;8f~pHc=_|~G_r2wL@vTycC`-Dgf)yYOp&0n`%vZ-wwx(TqNm~Jri0>_ zTD3W9Mx*qPtUcH>t89=_R+hH9EomcZ({*_*<-pZifb&~NQ=-LDU28t#1<)KB&-J7J zduUtj)nz`AD8vBgM?3c}43x>m@Hsk$PQk!EhLIymOB1WdahzF4TcPi6Fs&Wh6+JNh zL6c7xqfLj~LD_0lY>+w%hAJ(O;s`F?{OgRgFKm!t$72hJ;Zmf$#QL=A*Q8eah*;Yh zay~f`&Fd3e1!i%qSa z$r1J7`E^m;T}}7qea_1Pi}zog`^;v_|8$TCWm9xPMycj7(qspV;=pKzXQGReoX*8; z&ILawq6ji1@<x)t&VpGX(@Uqe03Vap5Wu-5RzxHl8(h} z#)6U(5>>$D$Wt0^;lf5!83Z-Z+M}kaxmkR4(VI<9|K3@xDd{Fy?+;d>3ecQ(6SCE( zU7H$!qI{Mx^i~Uz)0E`YhHJG#AWQ{Wr&Z0}iwo``qcM41=x)vC8LWr!WL4PD^Rqo* z^qv|v#RYDQ^9GWKUR%-iCW~wI;p5lU?;>hqeFH%V^a!l8!!`{UT->D%BeVxFlGxot z%DLnZLoUwGtG%)~X|{ErJL^Diw10!mYILS;&*l!E-IJO!vqJ@ZVW!wA66g2lE$<)n zpIfW&d^E;-=?o{4B%8RM@sAv|LJKUA4DPc$)+g1b_qh062m!o>ftqy_7Lv5d{tY0~ zlA#n%4SE;>?iv`iTXf|b@`Z^ezn8QZ&)33%FXMTICMsd&@3R;DM{;y#Km^E*HVnA~ zs?#y^FRbiIz@JNa|HhX5ES#MBW$>2N7d1MkbLTQ1s6XU37BO4O{FNP| zrbre>l=Y%AhZ;|?_-EapdkxJe89W zJ3pdLrEv-g;T{Cd;)Uo{gJw=0bx3rz=c>1ocJ~t|k*ax~lWlRi$q!xpc^k`3&((T& zGcDk}dp%R{=PcmvCX462azu`9knfen?$Yd82qY;a(gA)2u0MFHjC#)5y}0czVLKc> z8n;<|X_8m`0rwaPAtbS%Jg|5UNB2}mWBvtuzb7%jfFOfE@Bs@ox=X04%c@OHHYOy~ z*>jd{zNXf=h51KgDYi;%XiPCjr=C5F0-$_zuBCihT?lxg@qT1`!B4TFTx6j>+3=ek z>YaTAaD*Ykcq?ZLWX-FFF7<4b0Vx+;uV1udH#e3C(f%8K)+M7If^%*=T0QX#`+dp} zro%CoasN*PIK3MiF;#{m7J9UJfoiCKqB^Y4x4!TfKvT$;`0^Df4p zaEdO~-c1?a49dF_4{`}z4=F0GpjI)$n4Q0xsJvSwXczlv1Rcr`M=j@^p$LZr&!%`wKcYjd9!_AqUw zA&0{KWfadEk}Jk>liNwsElbM$bkr=iA;+r4xjfAptJ)n;;jO|aa`u#YWhfm>z4tZa zFgZXNU2ZiVROKUjkki=H^?dU#(HI9+aDijr=d3&`U7?oCQi*S8C&*#NW8HZ3G{7RJl zX6$q%o4vLT2H)mYinqs2ABMS|x6Y$M&*;cuqIYkUP8fq>w;^z;TI3_H8f!v(@RoBZ zi=Jm_Ve;ph%pDoc0ZW8Ln=dnnj$fF+pT)|?*l;(!Pyh}gqzc$z3#MTM-@%No7(*>-g^6SLS~2Sg*JM8WP3EHFQdmu|9a=57(gz_w)FF1^y%E-J)g&_?e2 zxOXNLC7a-JDR00IcxngKhulN-5DPJlPN?oH z!&8btz-)w7E!O79z$iD#6E_Fibd=vX{I0UFeFM9aaK%!^t_SF*IwT=ofucNq1@>wE zOBef?xW*}iYOqC9o6+uo>ObkIKaqt0!_Y=`arV6F@j%saYg_nQ_JiJPc+i}_C8x0h zN8(jzJ(`Ks)MF+TOSgZ_jm5?j(b4{`IKVkf2cs(c`+l4&8YEfgTZbBHvhzPYlg2ZxuBlybZ zg|D&(S(}2+WIZq@I~Ol(qMWbKS1vC4Yj(V&T13Ya#;r~vYjsOsa(rV>Cd4L|^GWZ* ziE<6)yc5WHq(|NXMkZTyN8)wuPfmC*qR~ZV-mUJ2^Gv+AuzYRBHNlxg(rX$M*E~h~ zyJdT{|4)MD!9~z10tm9|hm7W7Mv08g;)^ic;vq(`odX9^V$FBh=E=e;aFPsLILnvI zLfRor5OPGmKt&e$;BN{pWO>|s`_+8<7COOKoM!7a&ieJJ3QwDqMDP33j0z+SDhhql zyt*&D?<7gPRmuOp=yC>FmgCx_6t`*xDMtC)RR+)Z($Rjz?L|al&cxb7I?Tx~d@$si z>h>xFnUKZ-IL`weJr80LOJK0hn%7>OeeJwl@`b6fIiD%Uq^r7tpoLR2Xa2^AL@VyS zYF&LRR29;fP#&9)R+HVkYF`D>V3fbnQmg(dGqg@7sWG+(-EsAuKhwP2m-$*fTnheo zU9s@|DWr6Y=5_0U3n-xG5{XpkUrE#3mrWjxLM06?N>!?RoI4*4!r1A)Z;%$FCIWg) z@4|J?9NtY|zfCqC;HkwiUePn?th=(!tJSBnoyX@WSLQ)GQaat`cR9R-c2=sk_e9>@ zBz#{#qk<^8S9QEQ;HajKz&_MLh!t%SBuvLowQIP&9+T>RjuzkJmV7b~cWiajay$dJ z11fNN;8&jq?$-3jyg>WhM~GKzh3yl)Ncu`TACznz{gKpvCcNiy z&o?8_S4Y{BFV}6~t02TXuM_EDKpeEp8g!(sl;8N7cY5PDZR=#HMN-)IT}08@9tchzQzph!{A5KtYQW&gsOny>Oj{PyTHQ9OQ{8;5G~`8E*^Fv| zOrJEOcuxoO4M;(}@CVmeIt3LO8S~UI9q$bib8y@>Dq*y;ni5$Wu=URFu;CRX2Mo*k zzHDy2`s^BR0;XXd{3;euu)sus5+KO?24LQFYmZ|QnwM3jBL;#Msl77vdW7_`tF^ox zuG#!d|%tz4IaIE1w%y{FbdB?>A>5>__H z>SD^!uGrr{-V9dOXSwyBkbyAx8_>;Lcz&DqrHcB01rJ5FyR2SBMgNk)qDkP2y4&yI zWB=kb^Sf)Ti9564N!p}>=6Wg2Z}1$(^MIC?3%n}juKonxxZd69xO(aMrm4*%D3OK5VaBxnB55lh z3}cWU7(;K}gWtpe8zgMmuK*c7xQwwmti|XDmSc*$2h$me1D5TW%OTST{cU}chH75X zaSk?iQ(mWY`YdbMTxNwE$1b>Ak4)}AdMOWvSf2a!F|2J~0zyNibc|L{ ze`%e;pVyGUe+_lIbm8SzH8cqIbWp$HrQbM1vKw8@jd>=-icHIxQ=X_+S)?9dxw^7D zv)Wy3z{0`eT1hV_e?w2-yMm{ZX4P~-nc2o;`}#r8GF=-2GFw}j&b+%#7pRyEJc~LV^j%U|Yq`bZ1*3E6ZE5yC2gCV}!{J7!GG&9}^^EC@&)wK? zfIg6&TTiVr8=_Sf{4vwrc1IUsNr)UuNHWMSkP|sJFXUWS+1(iz*AF zm5n%Dt4x*D-+51%6}l1bJz@h-GaUFE#n~tgGub>h(oD|yr@3TNZrg-L>3223r0qtJ z48rXtt(VtzBdb8`j0_kZ85!w~rkvku@Qyp+EwH9+R+gIU(?=IZp_3%lkHq(1sdaqw zj`ub~B>23dRH@$iAstqnpPzYLb|aALT?stPyc{%-jl9Jj(Eok~r~UA_Eu6HA`L12p zD0}nPpYU8&rq<-Rn;(pZ$zW!uclP+aMze*}1Do?oO#Cu+c`6|aSw>0nf>M7z{8=hh zoEvv9l@i6midea2PV~NJ$B@w3HqU)n*)z zbN)NmM!gNMsuzl~ECwORSxu^i(88bQ4@@~|0d%gXBOXWKhckPmp{PF2koFNTK8*S+ z^wNw^-w+A2U7BG1o9Gfya&nvlhaugP6>;RJJ{IY7;@2Ip37QfMzxF$}WS;#Ec^(*D^oyTU4|G|2?q_Z6w(6JhVD$k0DW3$RzH~*Wx!KHW$u(d{^8R zVRcWJoB%FA_bYbkiQYx)J>8am%3(|v=kwxn9X{g7{*32ag$k^9jL`@}WqHyUw*Xx( zzp3o* z+C2`N(`oNR$5P!nkLYf<>o#vmYUjN6qf9Yj5PB2B?#<`>W6eTx#4pY^Bb~RTmGAs3 zR4q1lv56Y2zuzcEE?3A?lQjyf!%`GaKyQCo3YLZ^r1jEVVu1BMkj1q{u-ynSmoR<`canD*qk&EMgA@;Fwy1yZ>-^k=bckM<4JOcY}E#k4Uu(0AZ!=M!@ z|Fi04W#CGRTed5sW|VxkD2L`>2iri;qOM(Npd!^eChK6=lfWzvEk4ahna}R6dA`z*GpR;ni7F`*IdBIXWT9ySAo3#H4E=>&$!`!U$-$wIjr7Ch9bkn4 z7OE`HiW%AVQ=4&6`5L_%p4A#+F!W0kjv7t0h(%mo6j%{iV&y>M&$~YEN4TxmFim%f z*}#1(xB*=BZOKdiVL#S9r|p4A);&J;W?GNF$EZE0m* zg;-kRRfP2`P>zcf-2CCEUwDQ8u-G4B{2{ZCEYl|yd6>cU-ni?T{DovPHNsZNLj|0G zgFuVl=VA`MqrW_hsskgf#MN!x-UmepZ25V4<{ImLA9@O_bhL>5L;QbN*{Bk5 z{#WCON%Y}k+|&CZFBlrj)~}fH9;5>N(T)et(mKJTs#Z^bNdM6^8pz5azn$8Wr+8=* zgQAkApXF{80>3>ET8;wNHCLZ0cz*t>iBjwcW8@fX>t{t^Z4iaEyoqc>fj_4f9xbzs zmSyDQmfc^M@-`YR2D9X4c*Ry&}@S|Ha#3T>tQ`yGQh;> zwO$MxM9-BK6z)F!b*iWV#S(bB90>Ql<`eOUdIN~OO)og}$oP*WXfOUR5+`KieQ%6r zWVYrI+lmwF)ZRQqgcB<{-#yv~6$!K7b*n@YAJ5H&KDZ0kZm5F8fnoJR>!hb9{g7oR zsgBYa+}VQL%-*-6(8|I6>fVsluQ2({eb(s^a=L5!=XSn8xZRh`>nY(sg3{SC%KPbm zm9=QG8^7&ViG=;x6B41U;MY0cPa8g*N2v%$59}%n{ixc*=c{2|1rG|IU#YQ!%_^&- zga0&Cy zUJf9qe}N678bUBOT*srLpgFhoW`9SWP&319wZ5p{635x1UPGLFe8-{G|3%)+-1ZmO z)_k6rMf9x48#Ms)G-8hoQmZG95z57)zkTc3KxnhzdV*jHk}KS65mLhGcHphzmzkVobfJcvuE0vft1xU;gSRo`V0PN*)FLRzdv>O33_94lDn4*UIeJ zw|XvCgD1j9tq8s;o=T$`8mKKG;K^)zXAhc}Wdm-#F)4l5V14zoNpgJ=F@tEF zhuu)!h`yrJ*$_=gl6FykVE?$3)K`K9VeXgSXG3N{^WA+ERxJY;$D0~((kAHwM22+Z zRG7lPR_#JaqJm$_sEOB|_~BuzFI3gzuWX}q{@2;WlXZrrbcPA6NnGBU#|O_Go5vA$ zhS($TwMeGP+a(qRKMA*}M@$5Qv9ku#hBE2Jxl{?FnF zs}u>2({Wgu+SWZm*C=$^#EM+~dO(qY5uljXe`#w~E>_<5fot)*n#c;(jY?DfYJmlW z&rZ4gvLXy*yTV<6x2_h5F6JlvM?--^Ax2_-emAW2o8qxuy54>6#V#VZiV$bC3rj&q zZ(pr{RB4>CvhBa$dUZS2 z1#L}PPo=6=PW?SYwUOy~-WN)p+u5RylrVaRs8t-uU&c8b;67`1g{^&$h9ZMf0RrMY^rd~ zVPnA}t{U%Xac0<`NenaCn~O}EBQ?IqA0H|IMf$A(+>Wrk=$UT7H88qzV6_1abX|K| zj?S{`^hmp)W3mSy^Yy%=tbZzwS@pc(rRyS!`+mC85DMwCc)8{{U3IMjk$y&SpU6K@ z(jC+FmZWyTS$ud#va>GYr1LoT85qCauaSpOmczSFoXJhc=#SsLxk$qLa@|*FfGcl>ToA27P-?1sr zB8J0St>N>L%3;c}8R$!D&cVNZk3F+28M+`X(jMne(!$~~4Lmw|V$=MNrbQQG+bu!b z$^rZA%}F}Whta7tD))i%tF^`a24rvrdT`-lR9B2o;_103nS{?{4rEKoN|#%wsiCCs ze}%e@IfS-;eD{nbCvQp@RveM{{Oinxg;kP4c9u71i`lj-%QX)-3#~<N9y+;?cL{@P0MJ*y=(^#@kOupRx68yb5<^s;>* zBDiSuc?(~4fPk^3srUD;-A*WLpuFQ4i=Y6r((BR}Q43bCH?qWlmoHqKX#5AN9ukTb z(X#El?T6i+Q$&xey!iZfVY4CJ0qu~>a`>tM@yJ!y6!aX5I9Z|~=JnrIPik%b9rKHf z9s5d1PXk;kFS&6gWwNrkotYyQelC;pdI&s1?iHcc@|#HpW)_`w9%ToHhQY3`@LL9ATJY4nX=Mr+T$}F_*YqE@$O;~GqhwRSfn0{iNG3w&dfB2D& zeTze^E`&+{<;D03xHEH8z|5y6&IQ?jQy-Mu&Tn#Z@YcY^9#iFYbfF4KR;}&p+Uw)m zEYj_U1hC_5?@Tmvr{y(-N+O#6l@w&`hX3S@`5h0!w&@@Lu)^8L3qGMhrMWR1xEZ&< zV)2h)CjXXO_9GCN=zPzIH_|ODjm`d1ypz`&q9-(j_H%gd|15_t} z;bsa=Xv;?&F52sIaY>O6-@7$rAdScK5s!Exnr!5RJ~#t4a)o1(RFogT#kx}~I>ZZ$ z*EWIl%eSzgI(i~sgG^~QDQZF#$dISVT@DTdZvBZFV?IOtlVj-d5V{lsTdN>9Xhz-s z2=R+{j{aZoQLht#_3UoZY|AVkTbX&F%D!A`YwLxQXF+3Qh6^&fURlO77{+dfs8lA) zsQIMs9KH#TtFQyUAnQJ{JuIjHpmn+A;(J7W3d~t7?E>c(P$7Qmx#Q<@0p?0c_87}00PnH)1=95T+uy2M?vg-`ABrDhrPMGN|a6&2w{I z9Nc@rSL0~3q^!eiY;4TN&}oYVG zpsA(yj9-E}8=UU&j<65T;@a8mb%q?zBm)6VzAzHLa`%Yl)zR41SQWPanRP0e+nph2 zGT$-Wi(Xep+2)iH+@%^RvaqMo!dA)Yc2+ge4@#fg=HquxMBh%9Q(!9*+tt+3k*@8^ z&zDb>+lfkvIPjVVTk%Vfl2+K63V&LrP3np2sd-+L{%@A;#xCsgezwdYu`j;@c3m;Gj zK1&0kUM>liKT}ulZ!&kTM|{qw2*o#0%124&3gvhz^%HtuiTVI`R)mAEY!U|6nbF>_ z6?q(_L=^HEVCYQAVz`iNgMQjf;+zWL<-(I4W{(qWlB-j^0IA{kyY(~@m&kHM5=37X z)*HqkXdkpYdI}cc!M5xhwp0h8uk;Plt>v|u0f~SZYy~Rm|3rs-`iLtniJF7q9HZhm za$9*JxMg1GDQ)LxbYs-=3RGO%>4%hM`~nZKn7IPQCS>DIr>a`E4KvbvzE)Ym1A=}4 z8reFUNmO*f8=6$v;};8663{`!Lu!BUvnZ zR;XIH+BIfrg&jXa8ZKVyj zw*TSxtt0W>fzY%EiPuS0z%EggUUU?U0hSG^5eB*Jxw+6=L(k!B#cbXrhsC)W za?nr?Sr~Sh(>}QOy#Pbmj7+wDNNF4>9yc?zPNkH0iN?EnyTqbmv z*I*l~!jEZjXr6>j@F}0=(`XM;mq%Mt)uF$`!YsB#ww$O_(I;&CFDgEvNn|j^D=9y- z4eyboYkrk!PS+ey_3K6UlkgLD%A6BJDu5)7J`9`GKUaZ#$ZixrEC~qy;5aPUKwQpU zm~nzTUP}`smy0I|ETL{7r}&A~kQrp=Un|C}Nlxd=ZFfnBc=u|eXp{A?nnAq4H@WL)3C%2Ma{QFcLZweSW~W(GDs7d-?m?g7 zH{_-(bhTAUpDurUwfu!EA>jFvtP~3bOZH$w5IyZr8$Qn)g*nSlqyZM)zaoEFebW&8 za9>j&yc`$q@ym!Copth#52<9*kFQ%Tecjx#?_L3k*n9=@iYix^_p_9gp1YTO&JaI` z>z*DnxK?Ke*TayC0&X#EpZZN28DLoKdcPvLKY!BLVU^m&oYww_7EXDORj?OTu>&?s zo5Kg9#$R5Vws3?h`5CTsR3gmP24+#tZ49IV>5t+7 z6KOu;5xR`0K!s|5m7IH%{pzreNe^vyJY)&Sdqr6t8rKtP^EPMr zRN9o_Ewu59yD_0D?Zf2dxf)@M%PUdnp4<4+u0JnAO7A)(l%vRuSaeEqxm2J1^`S`{+tPWXWzH zAKyzqF+bki`iN5?*f#3&{#QB;mh5H^H5C16*>JXGZ5TXB$5t~ z)RkX;ZdGPi>tdoTWM_-%L#KypO==`*Fnsx}OKPKK^X>lKc3UlO43&u?pP)_PGj;y# ztlQ7td@?PK`yq%c9ne3A-qS;5uZJ^FWuyLYEr1%G&1C2+FtONq_lsS5;=zIY6aq~l zb65?&fM)f&{c1#{0CUX<+0bp%GpeFB~bu|mz)RS@lJY&r|wRlrr6KaMvTfyD5*-vYc+Q4JWCzevG;5^ ze7}yUpT68|Y~GovT}LcRF6}L}RBRgqlfNO0WM3}fcluD1{Ie{oA#IyCb)AmM#aHS9 z!>wFtpI<+t^jp#Tbjl^HH)G0#y`3r5y@yequrXTl<*5)$Bu0ZO11-U$HEtI5(ZE3R zm`mgJ9-+P9{{aY0o-2OK9T)bsMuE*oc*)2DnE719h+m2nMo2r6U2{-@2KS&wujxzsXU)m z>_U}<1v+?bXE_eLWUCH%pFNy8WE&eDl~q&(Haa)>X-l(BwS{P9oAKkKJ&{S6;9;5K@kw)Wx-Sg*YU z4l+gk9Vzi;w%kpt0baG&9o;-89pJdcRrk);KP*dUmg60P?gOA!<5|=kfLC;6Z!Q5u zHf}W7cu(QNlNWTg0_DJN`FA6>bjKl>&+skqbu|^#JFlp zu!PzywOkMh<?d6uA^r-eIoEKHhr;n8+On7xF(^I>2S%W1&yE< z2qJ7Aet8H9V1~p)O`Omgu14me-stl!H0%x#q)%NMMpCpvZ9n5jR*`xytRrq}8<8$~ z^{5xFLXvK)0kEw7dTdt_igFzODz>^*LiF~#QOmo{J$|+FO}PvT z0D))laiN()l8+%-cT|FRXc5hF^AyIl1b!ly#1{iJQu-9--DlU*LBVM+<2@u7qk)g& zd|omwc!@u4rYB|7>@1rVc0fUvwwg5eJ^K+hQ!E@=0gWo&47;@7-EgirYbZCxgH*jjD$vAqwtkL4Lhslp4KeEQ1#KbEqx6+v zS;;+FZW7Nu-ii|^o7U8hnuC@5Yqj@=ru@v0h2D#bT`VL-q)6PoJ}_<)yuRbJu01~l zsoyt{V+PY);p2(zHTBp~Ra5yK89MG@!{UtpOw64r19IZoo>arYoNr3|{@S{Fc;)>b z@Uc^)HIBgSC|CmhnTUvGP|~F6_X?ced#k%|-!3p$IT&87QW;f?W18>@zfe`}>qdvu zB-bL=w-Ua;wNBKUvvlJoMX#&P48*(G>igw;>PuSjjPmLaiBLY^OX%qGf&lhnKBBj= zH~5NA?{7H(@TNQwv<5t?j_r7N+r=)_q%fNVPQtjsx_Dx|yQPX8k$!*Z9P~w09IF!! z#$0$!bOjp(aZJ99Y`=RFYMI7)*T*AFAM5_28IRf0;3B>%o0k&*;bIITPIyuF?%JQiKc_6)!8*eFIAn`sY5lE3@Z~wMHR8hD_09$R z-*C(HFF)P{_;GW5eHNq6fBbk!tE#>r@?QIjQ)_ei$47BSHAztWC;jFwzHKiA zw4u-Fv`u?qS{Eq@(MtOjEAIBdq$0HMJ)DDsbM1j@9ah7*3lU*0zLybu!&NI#>n!o# zV!NSo!e@)S*_PMM6sn=v(PD?hS&x)#Y*^hI54ZbAdl$UXX@#-j4Z)*$;x9IL3`0{T zRc%U|*7|8{X|5eYT_I+kV;Y;O-o@9T;Ohg<4+CD}Bx}&i!i0sNm+0dFI-0;uB!e4I z14~ah0DV+MX8mMZkC;zox~ z|H4s&ioNtp#v}Cj6t@qbn8e&R)EQGdwa1jq^RXvLuyDjrbr-YxsunW5F)(l+48Oar zGP62Azr8mx7i3sF45|{==B~a&H_nTk7Jl8;^M<5Q=v5c*0<~hr!Ab>z zkCwB*{!k}gXS`cSrDE_t3Fo29K8R!=Vy*`9&Tn84#ql)6IOAB*Hv~@%K~+4zm&v+U z(7y2b`spUL3}A{$Ei zLtiQ*V$7H5W3mtYI%upx6<|9SadC`@IOA2|b7{@OlJ4|YUlV7fTvpgm+s4KZ4{0n{ z)#sL>j^CEX8Zk5RhY=<3dX1sn&x-7<{0vd+86@|y465N0r{~)90}=0h`XqXNubeCD zIV@Fq&o-|qg0sc>#HB`thIrd$G7n|t$f&65ue|#I+ z6z1RL6r8j;@GK}JJniH*T@d+1t1Uo@c<7;CLsAWyP?qQE_#sbA+!t*YrP=NT@+3Cpn>s#!hR?ppA1Yj~f1e!l(YLIxp1bZNaV0(PWK+w2j{! zZ5ms=-)BXt64~Fh(=4~ihqJpG;jyDP)=K~#L8#-XRRB5kpU+EcHVp+alu$}uqPnI_ zS5Es4dqy2Lu{yUdc>N%7{ITrIW6Oh1&rvPa^2bgEmLC!WGbw$d^ybckk)Uq1wM84c z&1o3nQ+&Df6D=Sqdpf;4^H5fAD{)DEF7+C+lRfw2eC*n-#!_;20A;sPnw42^it1} z4CUKXB>WL>@INS;ea(84eTuB;h4aLh5OlbkXkBgpDz}KVxBc*Z@r6UC(@^`iOnP%k z@{d=cgl#&%4|@B8nhL(7bdKu;(D%=2&s-IDp+px$185L4*G;uoh{m7qfXd?tP!5Ye z-UWO_fAB*06TnLXl`$m5Zfado;Soggh{<~EL58UT8ihQnLQh<+>{xdV1OwuF{^*W| zwr91?YIc9tp8dnenDimiM?O2Zwm}PO&||0e&TM>*|m*2Vwo~V~GS{sfFWS^dbht*XJkL&?m zdj1BPY605wn5VJ3K zWj2b^QBSskyn%SZfG03BrDw=`jZNFDc@Gn;evRM9nX^Y=vJUV0TQM;uFq#Rs$cvwm*;-H zLhrjN#Vsww@|AKjts=92BpNt;)AQ48)%pE)Rdp&)AJbXWdzVFaM@G7TN6I-xui(eP z{LgHwhl_kBnD+gi{18Vpx|nN9-DeEE!h`F4J{|MH)?_8X$TmBhrT5HsKWG~RDI8!L zbSsdgi+`Cr*T!G%zrv;}wT7tD_Dgh1+jfZc*E>H3Fd}<7tn72qag&N&aZP5}j zUFIHyMV{NsG?Z1*xL`tH^Bh;jOb_KIAr_$qgxskat`C70)%D7P9 zlyC6lf)oXIkFDt!1ToVC`dztCIN9$8pBR{R=#6%7&R`e6$9dLvP_ma-TiwkK<~DQm zf`oEsbm>+-xg$(67=kwFB)sR0&uUZUZ^b5LO%V318U)RBa6Kq{;^pw8GjEl;1fDu} zooej!=bcfl*JsX=a#27+D!?Z~mjoLLKBnK;b6z}hLBI+nD$`?0T9@+o4YxLR#!DoS zQ#|vN7Z>h;bq9EN@dI&A2|*jP9#{0+{2;W668wpVhWU%%vVTURH}9daWd~MsKlg@| zb88Gdsra665m{n)F|kkt)sg8~ZDJkuAgTBaBr28g1xv9rm;-{cM@MUB=-*&JGILbM zP{NQ*YI7^o>}847`1Ob3!ytF-An2NC)}=2NMnH< zfX$5K;>WZ{YrCv&>D|EAvmKe#rUP8pBzq6~jkjlIfMnjrAMwV$kS!oTuz%d}RLJAb z)xl=}Q2n6j-z5eqs+ z7InV$FW#ZCJ#H<65b`lyC7}nD%b$X11@oR-7cwey#TIh$pV>o~4w^}uyf`ovCNz7R zl8l*fqVHbVV$R(qpURtHa1I+MjMVS$r@es11*GR;x$Xvv?tGX#_Z~0PzUhnZ10=CZ zJSGJ~slflwq6JGq!GrF8WQp*r((HwSC1nr~h?Fy6pXV#=*|1bM6mjuHrH=2OL#h$; zSm1Lp;O*|t9cDpP^QLf3H}3+vh3^7651_R1->SY_>5d-*nY^&O?a%05eUkb9(#~Sc zYg4xA`6sf7kH!p^UQD@0N2rux793No~C6_+QqJ2p^C?%q*>>$ZR{%9EE%Ier=nuQJZZqd%- zah5q%a57QL3zd1xp;IzcjY--}pyh9`t+=crJpb&^pZ9W{u1U@}q2d*f0PXC4RYrrpOP67jL_bMzVGc-x3ZR{35V=Txy~}hWX`r zOT3l)&gsB#N4@ou)7LT(#UEuMWeFVDlFs-cIy*}`I%hKSkCK->mRCnz$-3+HNCfIg z)LMOdL`T^ACiNe7G8A<7)jW`=&fqCN~#QNp?NQ10o_#PZTTGelE>EqX|NiQ@zPy9p?gLC<2BtkZX-@iA(@|y?ppl+R{M8!B3Fux zmbb^(GQRj%=P2DV0QEMI)VXoO4%FGzo-g9RBW^U2V4|c{OVE*a)Och!r4&2#ji}<0 zmbVp03Z<#j&!R7^MB%p?yBOpwPQ#3&o6xWqMj9vhS&VDnZzgFz&}crxOnw^4tucXS@gq*vmE!dTyHO z_E+1hXps=oBZ?`8XN!{fzojFMv)2b94?|>(;`e{basA2<(n^0aMvWljD#~<=Z9i#y zc=KU$W9@B1^F)R|i4)w%#>3+k6RR7X!UrS}ss9xTy&RON5}3)17>YUNhDbIEGM=t ze3w}KraPGsB z+w+F_)_$zoSHw{x79g$tVN+H=X2N$rwuh8!<&Ay0g56vFL>xsRDEfJKsjHD`HIBT5 z1uFwF@z6(hx9*d?iwN#aZ}{9PcFS&cuwqgDJs>yWd&y*(>K()jSfAVU-A4F%|1g@W zSYh$sioJzYpDE2M2G7^0Vrqu)7vOro@0;C2UvOWVS! zt!$V#Jz7nI_uqao0ptEu@8MXWdu+m^McHD0jp^|yS# zS>rq`1%#HjM z1b!a}5faUE#Rb279qIgKUfE_5Q;s$kLodroSf1|zu3WJxw-bfn%&^qR!-FSc7ZO3c zQ;J})sG)uhDIx)4(vSO2ZkGN|-M;UI*(Xqo_QIe{<;e;DxfZbEi0Dd;uJr1CjO?1G zwbj=J2j7r|U~1fFYIELMSKu2K^#Pdpf5&Dd4Q4pzR&_zhUXUyY_=(cvcV-Wgl61X> zXVu>QnGe(U^<_5lmdB!n;N5wy_+%9HnY3K?k$9heW#nLo1SfhA`_pk2^1EH=6u(rk zyFM6*JvEia7PXGIolz2^WFilL`Kf&2_YmJ7(<%X;5^>qqs?R~*PLUX?76ZvH_lcsh z+u7(Q6n?a2<5xY7cYVgJ@=6TBV<6Gokr@)IG&Px2KQ@1mnN)evlIcx0-{GULqk1Yk`RE9dkIZtzmV;fI}^K|*hKPCV{ z(c0D>PQ{Fz`(35`KL$*uHPjy_zmi}2EJK;Ul2Yxqn^BSGcQ8)Z$xw-aYtOGHA?zW zWh$!Ez++c!!n8N?%2^%M9>n3)x+^5F0JH>pU7U8XIV*-D>4mz3C^_3zKmvn3+5ge- z{I}H3;o}r*!ObU~an3XIRxgI@%7leg9KZ2O^!0#<1#|ObkvR>&6-G`O*~GSU?ZHOAPe73pEzyhC2K1ap8lk4 z)*?jwwaU&k!6#WM(N+$vD(#c^`kmN0Kf8(0xGN4e!2tB5xJnz8=x|igv}?EnXCuMSWJIKV{gsMw{{Lqzhoe} z&-;3+93fE|XAw`=vj8X;*V_qT5iOf2_Qck8-)y~HyLT$w{~9+4O#x;2ZV(shOJdFF z&r9RsjEdjv^ppkch73lvQbMBbr>n(hT9eA&MzD?@*iVU1*?A6Txljtm*(KRk*$oQ0 zY_|?5P)>c}EKt|2lo^P!$Y!0)FyFt^jZNFZgJJ}_Q|5aiKjWT+vfna)fJi>1#^l}I z^`_}qJ*5n9I222OK)7u)p8i`4pn5zE(-5#zFs@{DhF#>S=VYX)Pc@2WR~}m|?3v{# zQFiV#wD-jtDjXD$Tz#?BZm4I^(QvXZ4e-6@bU8b6Uihh4^G4BWX4Kp#jdXMDwLGSY zuGe-R4Bc0BosZ!-ckCf}?ljBXl?f4X?PIZl1~M^x@bwM|IE=Phb224{lW6c4t%9 zM`f2W2EIMdSWp8J@^`xT_8lz0?}sU+2t`g1GV_dAvB#w8y2x;eQ-G{)%QZZ?qi*7+QviWY37B?gaD#b9O5 z7509kuA<2b+qW4K6pe2F9XS2|I6>^PblW4hhIfpUZ7H|yIa4;1^N+!}<|{kcyp&3c zP(nj?gysC{{*iK})1TJQM}{t%JY4Y&4KGxfgoQ_u!g?nqiX@p$|$OpZ@h z(kobtOrT;4T!tF5kk z^opn0D=RCDhu_6V^(XLQ>7^!rRPmn}Aiv|@IcpSPf`JvF+YwjGYz+uIg!Q5Ar=N`} zwkoCD6H8M=3S|jm-mcDN3FV2L65l7>cPa=)8+ft6zCzxjZj$h`_fhL4wh%AaCFh0e z^s37{k#}^$`-4U*Y)Q~E|9q8{ogd&~Xz`dysr#P^Hu4g5irKwAN7tR{gq)llvEyO& zdJc3DNQCKD;?vq!Bj{1S$NnUZr)`3ayQc$7up$NsLc;-b>igt~x^8|d+huCOHpBLb zM><;E%)SG2pHJSFz8}AdwKa?SoVU%v>@_`N(hO}R%O(WgO6h& zw2X}>y%kuN@5VQ1t}8AND-pkW|Mia1yiEk7@2)tk@4~>Tul~0Uq~`iJ*yu8GDHY7i zUqi1><8ExqKm!7a->TuJX009@NXNe5&4KFGs{@iNwS&eBuY;g^82Yu@L2EM|vqnPFXk`l3MZ$?q+*B2IPW6O@h&e_rG*)QsUl+$=dE|89} zrQDA4418dVrba^ba-ZhD915s7ckN~xHwPkHU<34ql9lcU?m!2=z3ji|boSnTk89 zPsl0qD(f3{sB+otRfq-MDiM?HFc*E%B8$z+rQAG`xkiobE}9bb{+R27^(C5X2uxX! zv2i~M2ER5bVg;TfNoWm~@3o<^*|J^yuxW=+B?c z_fDNTS5KWry?1)^qC-jCjJ#cVBvP@N$V9=w&vQ^0^-?=^rvoLYjczAMLoWMCMcGR` zcn!7*J7Q8hx)GkbWa+~JU7h{IPY(xy)_^_lkWG(&+WE;`;lE@S%t0Ep(P0%O8Z~T9 zX83b8+?sxhl~;JLyU_Ofz}DX9&r52RQeU#J-V+8vW<;;QEo3exiIv&ua3uh7##{LHLA)<#j z>~b!zKoAqd4y0YHSC@^OE}ual+n0CLkUc9V2*Y8j8jZRPJG`T|4f|Z4O|Ec#q6p!R zru+Q9F5$BouW+$AS*@qQB06=~Ny3%6E!SfEYSf~0mo|LA%B$QxmxJRX z$w*f)SGxmsXX|PA!7Q{w4*&rP&HQ5%_HaEk&&83slpOGEbk5jpETv@Xbgj7XdoBbg zq<3id43SJuy5kyyk<;l2<7?N0W3%6V zgjKl9n{%)FG$SNa@~Fk*37J*cw!`DdN##?ilv2GHQcz({CTcXDttVFo70c_`lwwg6 zgk@dMt2u!`oQKx~ODba-l-49tHiR>y7Z1J z!zz{Is7k7Ss6aRx^+!%imi7d@>QQyd?4irCq1c8=l9x^AQK~b>bwWH*N!Mp{N|%Xw zhfw3Q-%H!O@;*DO(Y}|y@JbyJNPz7|^>nJvdJA{hQj=k(#%ffgb!(}B3=+K8LSWLy zb$dYr%}Xn3N@0Br>O+QOj@;_kmwi#!SC%9`hoZqzCC$mFXYU7Vl=f^~D=~Bo4WUO3 znR;8Q7VkLDI8Zic7KesBF4js&8po}dn-*Gx_oN+ERFah>PN$v$%5|gxhlC?_4CJV= zy^&L%m)%vLUK;Oe3^hBMY}-VM8?q+yAJX2ExISKNk2b80E&_aU^ttn4Pt_8*5e^2c z{~uZJ(SH< zah9@r#{w}OX+|Q61p>V=ZKXzbC0|Z1fG z?wBU%A=MAr_AmCYR4LhvZ1_WP)g0W_d5%h#L>&}-7OuUnya9ZA`k(dmF&z7cG|m+g zZ@#eIZ7f~Yedn#-msNCJuOP@4%7w8O8ef`1RPpjA~uF zWVVwUN^g6R0{vddv04n&oED}z##jVxB|}Ap&EHLxv~i!R)TlI!fsNIj9Gn-al)e=p zvuB=j+2`$px`InRtT={5jbn#mR@0TXHHHf7mePkBh7>F$CQA6<8ef==xaR8S+jde! zK)Uy&@mA9MB)&y6Ludlr(u&oimMSBUwrg0tAy=NI4u483c4sSC!SJ0PLRE=`6;wO} zSKp|mwuYq%c7@G5a8!ewNWCEA;|&Iwx~g~#gRtYg6fUJue^)LrpwBlpo3CG#BAN0V z(cpD#O3`K+^?BmZ*g@bxTn^Gb0&ZZ&t25PBDNj@=LrhPFjJQsEZ zm-KEJ-Wx$6Y!j0d6}+K-$MXPkPCGkfHC&@dsm?+CgB!*-zkopVVz*kT;%#vlYu+9P zlP|!4*Y&r=;huT9nkYJ5`@ZmjOUCLfEQ{}}OQvYBz=D0j6MdS&-q4Ww;Ob2--x^TUD$AxUj1V4OA8Uly)IaX zT$HvdgRfB36t4DRtSIw=ju``-s*uS|#e5@4p&=0)2d6;kRdm79WQbe&9f2%;p9^Ll zr#|pOHss>@LCCfCL2KHfVEq}tC8~y~(|kZ<3@Xj_qWRd)(z!1eVwhRG?hOEa0yog- z$Mc@7A(z?XkU2`cJxaCifFHW!aJ0HJL+EjqRHV>*#9Yf9)uV92D6IQt0Tg#~x)`y# z-;VdtKO4&fSes4bK6mK^zUU+l4}Z z0)W@+e=e3vJQ*8-QA|R7c3xJT(^!6(ot=FsN^@ZX#~VeDqMC|UdVkeDjspu5WDGtA zqZs|MmEVZnrzi6`wmHa#&-wa{{p@my0cbYS{15>Wx=dX1MnXnx4SXB~0s32Lg0_&U zL0mdnqrN<<=LC0SxJ-%)W{NUv2OAO;QIYsWNgDFK?|Hk){HUc_`>v$iuFCYJ=G@u5d-XtXc<+_*5vb|yAH%Ik z8b+)EBU;1w9a519%c?jhSjW3+!ZY8jw1e(8oQr_x2eby`m2Z+Tj*v5uMu>bH!9hCy+$Ke+XG5Ww%nm@yYscE~HfTTYIczI#VcuTWq# zJ8{g>Yu^np58wo2|I@$duT!5GmZ7%pLS$I$abZq}rf6M}F#$x% z#Pe3^s0KOOYPzc%!ENdSfsU3@LF}*`*btd`uywzg5s*!P3ixEn;o`V4Ro@<(IR>Z( zs44e0XaxQZ%Gdu-orRMr#Y@XA^?OW@_3{$Bq?|ipyyqbB%c}K>A zj7n+eC!-na^31+kQC=M3S8^&P`y!IOMGiGA1&h}R8{O9iuETT7#rkA7 zU>!2gUYZ5K^j(>&jF&F;>U9+P1-{mKxDl}E-CvcRcNvn&EsZxX2@$;)Ma4Q!u=yY> zJDZoEe`FKb91~d+FmCg9xZKwxGzq%Bz+|4lZ!o$+R zNPJFsrrt*TWM?LcIn|2?Shy|)jSJhBx1Ua+^vRt@YUOvdn^v3J_<5p~Mm!CFcS2nl zpw4_A1Dn>sH6}9osYRlHfh4a_zCZ_vs1q|LH(4;N!WeeF>`E=m>qIwDVd2|` z;%X_7zAPv-3KMD52RG)>@bb91utm|(rkklf zJPwRB;Cvq0t-tMTw#OyOVEj~%31q-Z*}gm_RAk9v8|o8_2GSlzamY*ZZvBU?#v(6_ zhKl8it)*4zAVR{pcOtIF`A5c_WqP75olv zSW2m4atn`jYftZ4!fTA&a$sl=cRP}I@!=SO4lR!$`^k7~nL0SVfpH?(9E>m|94{3( zc-wrI0lLsMS(P(}gbN_r7zUJbB>GMISj@NG8;bZE|yANFO;ubTIP?Mi& zg@ne~s#N=m#NQkG0X=)HSg?++D9_-9JUKns^SFh~Osno#umo^pKF^Jsf${?P9svJm z6a8n+NF<)^-((TU(&AmOtps8Rpi4nj_s-Q&fq#MWeE_g2D~2{6frEmAc*MjE&X90e zthIj2t_=!O`6%iOKNwL=MRup&SZwjFD{2a=IPdmi*$(td9}7f2EtBBJfoU~HP9C_G zS@S#Zt!Ibq$lDA9aO^9ylhfOmEg~5gNCd?Ju8!34oPtNy0U^56YK zmEtcW8w#~EQ{+f*_hfzVw_5u=yX{Wjuazsd*G&r>06q(Ql-@`*>NdB8?Dapi2c-az z+jb9Z`1?yorktl``Q7d{`t_*5Rg>a za3KTQDbBU~UKED3gf`A1Ga8;XiUK`x{1=p_Qi(@VihJ(E+wVnJ zZK)V(t9`Qc%34#2`9{$yvf9@yDC`*O^O|4{EX}kt;Y!xnW`*+qG`~ni?j`X^= z%*G9^Yc-L2C3=da&4Lp8A7gq8MzTigF2);Ji~Adq0G`qE$OpJl>i#W)3smYAlySRT zyw9w82E3`(De7~U?L21a7UMfH9=_C;vOI@0i!P;`Fjt_aq&bGnw`xGCGD_BCCI>j> z*LypA-!@;gXfsAMD-!n=;{5p=%q|UR9rObf29UYm;H?2sG|P*V<+xlMhvFL8Yy=nv#$`b~n2?dq%m6ad z*)0XgJxHfEbR5~yzlJdy7~03MSjMW4XVYiS3Oz}@AvTJ)+SZo7;)nEz6W}If z&48WBfKxTMW1@IkpoQjNGh)TiV?i3(zVXh69eOSrHML3Q7Ma`ImkHR~(l6lp@09=C zua+*`sI{XFyT@t)Y^GKelM@FAXSt~Ua@%85e{K>%6(JBE+!o!YhU2OaR z;njt=1e#>bnmBI^KmbV4Dairse0SFc>3)iH5zmq80227%DV_t6mAf`NE>tN>CT1Dh;b z75@jTZ^J|oqu$zFa$wJ8JqOY%1oD;ZIe@=_;{8s%ciz{?kO3%gROfF@djSC(_-~Z)UilUhJ~kK(wENRnm=2_9 zvA+E#`oq!FQv|Tj%vq%9Y!Xr@kvBI@ask1}u_?oBDMWm5Vj?{Nwq21SoV3L%csiT| zkkaM(H0fm{WQ0ZtZXmyb89C1tF7Ig(=K54x7|#5MdA2_!1;dBTln(? zIEd5H+V43U3cw-MVi3i=e$NF>j}687=6n@cSC~4@U30NID-cz8IJ(o@;KPtJ7S~7& zJmEY2jXg*~+wMgP?yA@ur+w|;w1!a~o4@~#;cKX3QKFNQ7_Tt7-P?HiSHx|`MfBqpAUQeb$@6@k&wG46=Vbat>I8{$ZvAdL)|Ai z=E&^dcyf#AX{sR<_A40}9p7hGb;-(g1lomwGdX6>n*#f)iXkS^Ve{aP@!xsbBFxIs zewQ|D!?Kc`xO6MIn-FarRdTZmg*iN6SM&IXjIOn{2ovFLYgpzuQW0X#nNE>X^7ejk zV74r~_Y@v4y=n1m(j5Aj|HE#{Qz?eHzas`7dijNJ|I< z*!r9*jYws1=t<-PiUVWSYg^Rl&bpS|EuQ?nM%c9fBlvBQDO5@OH12S{np}q zq&|30`P^R>zQ|JGh6h9AxH;J!zQ`Y%Zyc;(JTZN?8cuE_sZ$Pt!w(}SYT(~N+U|Yk zQ&qRqzVruRA#S=md@KN{WO?pfB-YeZS07{K*RmTAa%zKt4{W?Q_;)@ya^`@E?xo;s zWFSMyR(mI@sK;_&lGj>#z8l(@^z1;;p1+Zw{RCy8 z5ruR@$wlYI z!A#={Ei4Fz1}!85>)wfGJXbe^u3MZ2U!%MNB-L;u^3nBL!bOS!Di2sxkk=#;UxqN{ zGaY4RybEE_n-DH8p*E^ft{&xe2(O1ySutlsE(2pXQNi+!nvnW2fAk|nPu(vez)XVjll0x4heAfvhA*5t>=$utK(m@Z z?e=Jdj+sn%4xWXn{T#eJ5|eVUB8a78F3edB%E!4x51n0Ub0!*|F&rB6_rAP2n=>%X zTw781n4*z+9)_3Pv#}zZzRFIl6_J#AEuPwiKGvH1aL=2H2IqqotpXGdB z+*o^WIrH(sPT`sFRiepf4%WnZ&0bbc_yfVPlK?z}XKu0g5 zhF}3cY5Zh9+zSz^yZho13a;A;f@akdUwyU-mNNsjPqE~~p6xCT&qk=wwB zgAwTd9jVGcIT3wAb|v*gxN|UTDcjJ2ECC5e z*(W#63c|d7bLLmN16`uW{P$1x`7Kx+1BOKk{?o4JIEbE^B@G3o=d7)F$WT0O9v_9W;A@cixS7OhbBep1K9w3xlkveFw_!ad= z?f#E6$VU_i0EYg?x$gCL9o7T|gI~C5`UnKvscRPvK%4+GOmDx zgyR2-x}P~PFpM3GEf|I3I3NkR%Z zrqc+Y;ZHr8%w>wc*=7OZG|h-wvK<^ zkRjbWNV@&T;DW-@KP{{?_PT+v0zM44MVy>%|2sL)SVG(rIC!2{T7aZh4Q&q$3*5d4 zWtRg;m)u!`lNz~?_}1J&w3+&e@AITeuuFRcdu{H`lhRM^LjNc+Nl`&u1$MKQ|R%v5t+NkwiQTZK~Cj2~tM(j`eAWveR57Xy46J7^-PBncc`e3g1TUYka zo2Rph+%cw>46qh`tV>!T&$IknB*7NQ>*vIB1;131QI}jSF{AhS6V^(4b#?zREA?`J zX4`tEVg{rw9c4mC0L~R6`GIF)XnL=z!PMk+iL&^clDQ(@cQ~S6{cPiPvPO&v@6*l3 zJcoS`{2davTiB8EtbyOPgP{(E_7?|@@%h8H(?9yR&lCHY%e>?ZraP4tc;_po6Rwl7 zOj=F@)O^rjfFw>v*hJ{cI4X0P_s7paa!zS5EA}$EsZxv+$Ef3fcrCfg;`->?n-)vW z8ynXS9oQr^?5+V?q1)7S^}|gmAAkR6eUs4Xo^|xW!pi+s^yljnk2DU2Y_6V`Ay>T_ zT_@HEuqO9Am;&sblim8JJ7s=(isntripVr?k%Hjzq58E(FTUf-B6lje-S|PDfP$a@ z#068g-#ErjIu=> zbnEN%Qq~rJ;q*uH^nQJph(v?16TCEhE}LO2wN$T(7G^LjDmh&>sZKTu3u5h2{t@vG z7;9kmB*}ULo>y0)$KBCw_^g<XR$14sQw6kGFe5-$w?(GbPLEEsWKO@bny&rTc&%V!Wa-=}2a7feTY4#3D|IHR z8>jbk2vrX15cGSiu@=$>{HxA3w5F#aK@Pi)BoG)Q-v>yU+%u-8=ICGhF=d!5**H@t zvk6)cO{HZ1_Ds$#m!F7^i)(KVu?(*MiP!l}_kjPQh4pV-y0?`=_WZS%p9Y{jQKAFq zEXVEZf|sU5)W%Gsp3%n1jtg_p&_n?&$x#Qs3t7?7ZM5-R0RFCvA5`Umv9i1+<_8G1 zB?215L0iy+x&?~#leT1ewc4|c(6!NMdsXbWZhlU!`T7^;_DC%ZWr#jIGt=HG;On|^ z&%#$B8pwfM3P&p>$`5){@V}nHPrN1Qu@{U!tht<>vpB6sHl}FQo*j9APKK;{zIYEL zVcnCCc|bc=BKq=@D=UTX_HH^puKGUr32Lyh~~c7d+H&yu_N}ypk0M!0R0b z|BBtf5&=C2J!<_kR|a?Zh7AaR`_jKrz&8(+AeQE9rn-bj!W;*|&XZDi7y45>v{z;E zB9z5}QHQ&%q44QME`P&1-`F5sz!ar=efny-NK)ajfqBn-<5S3$m1sK%GZEwR@oejS zOqlNY^o?_-JAL`@KFWkZ;WtG*9Y5!xzP8_@Yth0+ZHYf0aQZ>1BIIk}nf|Z%$@|zD*p0+e|82^EA)9AC?MB1M&HIInp*qTF=>j7a+c8Q07VsGCsFRgxQDT%UV^!UHPiUFWv=(HCf{amM!Xx`OdRyv#PVWytGEe9g{hX-Jss2!88~c zvjhzl>@SQ6i|v-YlYBYlg+c8>GvHU0F$(G8%GNCefn*o9W|ou%&P1+IFp(6ZV(=T| z*x%E<_!j7v4Q>oNZ2X)?bZlVY(FH?v-m-?#gJEvRo|4THLDEDs$E$+D|M--1CE~{c z7Z0Lv)4gNF&*Mc^d^fC1Vc}JB0kJ*8w%$t;^R5MS1}ZXF=2>)MaOL7tDXQ{D<4O(&P4KV5-tE4lnLxVI5;58X0buoEnAJV}7J$~0$d{EZ zj9I~s66-F9tZ2mP^Ezb+id*XohD)i-%gbrxQhU`K2BkjOc52oL3L?($J>k@HzOY?H zoA_+YvgTW}=wsO+#jW5(yt)dU+?yG98*&Ld*0YMV5Okb)ZZg)Z7WmPCj}?%ZUSd9` zxQm3+#{8=J^U7yi?~72BHot*Aw8KL+!8TC*farv><@}gq9gSNC`fn32#7Hf+_Y=o! z1Ty$peg{s~4_Nxr6@{SH;y+&IJS2DAFCwbXzUija?#pBVEC3iTVXb29d$Wl(a1q2{7gJIX`hq?RTTc*_D(k5*mvz0FKp{hnNl zTY?gBfp~AkidCHjPNst}s*+pArcaN0UH*wDNKr&@o}#Ea=e2FmG$`kG->wU5E{qY@ z2CQDIy2_Ijj=eQd_k2dl^3~<|mQ%8d4dPUM-;R9;dM2Wtx&XWJud4Ky&9(NYMXlN7 zOG(1mR=Zi|$P>b+wkLY`ac>)QcBpbLrpLT?_Q^d*b!v?z1q#Ee9Oa!H9pCZ!F@ub` zdyxsSS1V?i!t=2|)-ZA{^EO2Tbb5bnyP-83z5H)GqsPj`U;mi?e4bEM!QMNRXmwPT zpf&mxW5uzuij?Vt@ws#R=8^LcPh$--gYUS#nCW>eZ|Pf+c$&uerra=ubtpAxphiw7 z`DiAFow+-~lfe2tWcuDGeX@hse&XZ)#Bo}G^v6dV(|Nm53Lm7jCZckuEt>T7H&(d2 zWgy{bUI^!PZ(f5AIcBn$m5H_xuHn@pvg|wsPP)C6f~YE)x?%G(QezPU)F!W;KpShq z()N82@rO#wEIZXS7vwlEgQLi28S9?a%>sQO z;Xz&}C?_2mf9p$Y^m>#Ao=HaTqvwrT1+4aM8%^ys*P?Bk z1}8dcwmTpEkZ{+#=9|^+^5nwIo{-hFn`YjLAv@Hc>pHM6Z|P*<@;-Mb_DR$G*dtx& zVW<#wUTgai=xv8DjCar86}}1aj>G7-hQu9Q4X^Sx9ppUg@dvfX&R|+|vQ3GD3~|cb zW>$4QXBzLq7XJ6!o2M08`DE=(g$>6Q92&HZaf!^$)ron0=3(=NYO5mKE3^I#CTc!* z8$->%bZu>Anz>3EU58xs*oPlb#$sL(JTbz$z+;UmiSW4mkKKin9%UU~5ZZa&SVr!!K;Q zXCt&iXU;$Jh2HA+1PQt7jZ<$l>OZGyq@<)|{OjxJ&`I;oFwQ}64DQwqaS!oHg5-f~ zKl--iuqGzF)ZOYFG5f)*?%8W;^5Cb0#CqwIw}h@d>o>{l;Y{r=7Q3a5L~FImGa)JG zUi%rCdfui3Sr7|WGlcRSTlElJh23cwwc=G4J6U|`#OjqZeH8Eduw$(}Uhq{vAA_2R zWkLJ2PjhlJ#?j@hbe5SwJ3-;1;I%R+QRfsC6#Ur^Rx_S)5}sR3KTr-UI3`Ik)4G}M{C6E(WfRw!pKACXyaIA#f|uu$x>as9=en?jE0u49xo6n3*J3of zm<@f_@+04f&7$)!GH1EUrUDMSPQ<|`+UDV(Z}Ev^IEoJEUCN;_0YzvuhTn{dsO8X7>YU?i2kf3oNf((s_o?rAcc!X_8g4qr%A$R}bVeg7Wx8N_ z`OkK8Nm)VVCZ=}>3WBD^9PBUPhlG2Pym2~Fw8m_vj%_aNAMQW9uo>;svS30M5G9>cKRPe^ZYC8bBDQP9pNWA zS;4a1l&CSUkQcU0jE63@h>7(EI|SMzv!8abCS~Xf=-O_*xgZLrd<(Ht?14-#j4nAg(6@~~Wb9(`=4;|| zZ=qZLDC%B-U>kY&Ub0iE&qk}>4kKV4NUW#VS3*OPXsFlGCJ|A&ExrzTHw=Mv+~9%E z*R(qRb;$$oz^ykcK(7V|zpU9JYV05Dwz&1jA1hl-(H8Gdnfme?2Fj3NWHTHYMR)T& zs*gbrKuPh#3rl#_z!vt6DJnd}nfuL{b!MgMl;#%7WnQ|#ZD6>&z)&mt1kdFO?z_?E z?K#{~<4YR@Q-{u~sVnYiU1*2KHB5l#zF})0E%S4?ztRru`5c1_Lp5Xz;6#m&ep(MH zQ*5_9q@ijId8)w(-tZsq;w*aQ{|pRA>-}Sy1iSDW!-Baqd+ZIn@9(HzUa(1{Qun*K zsu@DHpujt-;=))wm-G}{WE2z_(Tr*hQkRZprt!1;7H2l=f#DHhKnnUck~_m+E4t+5 zG#7M15UPa<>2xxiDwEzNhPr$>?`(BIb#bLc1r-%Wr+MxH%PC4QUf(|>fHveu8`8fP zD#Hlc97vs*(ZKHT&OWRWX+UzhwpcUT_Ecdp{ga#XaLg}rO&%+%3QG%6HadJ8863KM zFWV|brD?{UdspC}pWdw-)#x5uZrBrm64iqPKkQt1j7or@AYM?=ab@DQg7AWmb*u?R z-ObFWkZ2)89LQXphJdNg@a};{>AO=QsPE^&^Yje=^;ELdyAP`JHOM1djnLw-(_6Yn~L&E`fbyD`#5x+){S#r_#Z%xuHMfq$+FqlvaB=Hn_a+Pd}EVSq}H>$70lhvQP_;zSdksCkP&(`}&sbV-S z&zzIHZT^zNQ?FR}hvjE`{Ez!8;EkG9Re8O%dMYo0^NQ8aFw08t1`!)yc^J;M!8+Q4 zxWCQWHUx!Sv z2dZRcWm(#wKMbT^XJ&Ox4j+xDYrn)~HVyi#6o+KUL%Tz_k^Uq2AnEXz4j)?vQ$1tc0z?oZ9EbJyOb~ybvMBL7Lbr-Q)(2KK~VRbO$PKT+})^ z=%jvMe&VJur7u{>XiQjq)thuzkrQ3{zE%)0f0K1Px^wYS9b{+m|9T^hDOjjH$kqpN zH9J4AYWSw@iW-(;e3YM)<`pd22IeRJ2Y4<|npx!2+n+aNxiZE(t>?nHSjf3+DyfE-Cc)^KUqSEG;FS zal~wepOQENZpM=^N4AyH3EsPdHS4|RZpNYo?w#}FW?^fND~)4j<5EmQ5>uF{gFc{f zT$$cLS0axTYNnU)OT@qz>WmEO#`5(PB`)g0e*Miv;$xpex`=MCy7*a4Pn?VgW-foz zc_56pGFf>LT=g$<({xOGgw(KlIS;R+A9-kXY>T<8>xs!@fD{4fEvErZ3>A%MSLnQX z6DH*Ij;g8c!B}|*sijeSN@Ot5UJR5%7SIe(#K60E^Ysn8Nc$qe(1)1WC1r;)+>RO^ zNN~hYAF%?F((vflgj^_Mzd*zNkDqqP7AH*%DhR4{M2SU&%-I}%$8Tk=Z4*5qv8yta zk)dFSn52G!*q}uJX_&`8{Cm=wgH^FLX6z?zYIe6q7gstWBy8;DjzQkG2{!XIlgl zZwDTbj_3`mW58o&?Nri?1Z!R1rn7*X1D4&bU_SSRHCAtr`579M%$G5(uC8W^di6s1 z4EeTBVuC&QvO{s)r(K|Jq77`3feYZ^hY`qX5s2U(!kTqc(NW5Q{bvCnhRu3#$3fI| zU>N??ERc|&4=q$aSqqGPhyu|=2D`%Q_!|OkR7Fh1hSOnaz3;`(7MWafw5(t0nV{kI zcnf3afbcjY8tKy#X^4)t`c$$14X!JJ%SGM*xWdTvY6`?IrmRVseMsRnwFLoL`I);5ssKR^E|nX+5+mw+%CJno!@(Cdj3ekjQr?Y<@ynjVGet z-Jb8$+I+{V+y$-d@E!ygUA+J+T-~N%p)y*l`s(%T-wqu*)RYVz5_oW_5<11nOUVZ; z%FxzRK3F09|Dw@EshY|M&$C!>@ilO+{VUerkh^3BuPFH!ioIX-G!+YO)uKamv^K}d zEqHE7=TZHG+fRfV%gTcO>_3xF#EAq^Gmma*=^sz)L*p6cP=&~yg3!GmTF~|Pd7|ZF zzux(Q6Bu+D+jfMaoay#A!RD7<0OrQ2m6dB`sO3dsQ5spmbPy)(mdfKA3mY|=q=5nL zW*vhE`_F1IV}>$JJ~wRBkKK#_%>rS|pBjgjV%NLO@JhV(*Q9AEd42N;5hYi03`j|~ zzF|MIW;UrU?d?Up&PlJ}7wjwa(b=vd@a&%)8FY;10%mJ{#~CT*SV`TB_XY{=$%?BE zfb^82Y1Q|R>QtG$&l58r;vqAL)AFaXx95IN7Hc4{P3119vDbWz5j&W|R0VQreJ5wZs&nglvN=9+y(AGk(NG<80>BJAbLITQ2VX5wQ!k>YPzkQ z`;HyL_i>X~Xy^Bdv}Ez*{%;R*ycVQGq)cqAr!t5Ri=j5%Nje#H1-Y9n)gh+9v@MI7 zwZCL{%=<-65MY1+i`8R88M4NPfpKvrytUdgVrYTd-94j4M`mx z9f~8JcHw&WpXe6b&zs;HXFe{ze#UqjSB+cv*w1JrEf*hT$s{X#;?}TGnyOy2m^Yc(v$70*QXjzABURtj&g#1HYI&i>u}a z@b{S#Jo8i(p?nf31H(vvh>tH}U|^*!L_K7|$pE|(uNK+}ncfl&hQMnG1L?SqH9l?$Gwwd-E)Gc_DsN!!!3sfQ z=?ZNKP;+xU9zSqlw9g4_ku^J)XrbZQz@Pf6EU9!tO)-N44crxRF5D$crM`v8Chc_V zq(`C!MGd2TcBCrt&Sh}k@^kRMlE72}R?^3of3_Rfwu)MeJ?DA!5^rGL7o_U=pub4} znS!mri>0|o)fG`2^o8cu^+-7eR*V+AP>g22sn6GR?_Vc-NZB zgWek8WYxBaV3z2|f)2{q=df|0fjC5KK35-Y-G>V3v9UrS)U{V_y!0dZA<+J^lPV@k zX?KjFO|W|CbzZ+#lwx>35u%A_~*o0t0E#MeHZR6(564 zV;c+<$MJu15L?K7jOPUk?afvYSa01x#w?j*5UFBq%&{|B&1?@0e(4*)Vx3DTl^s2_ zqqOuE^zot*ak}R7=wdW$8i%05u0q-=_FsvI4I0IP8#$`s^% z@YD{(*Lny;6uWL0b>j6-S4};Ge&b?I$ClBgm!pMeM}qcwvMRQk#Dmf+fRByoz8y__ zZFm3HJl3cK68>QMcKP-Ylv9+Ga7#0F&i-YJ;mwT;P?ENC4rmCmNFC z>^-oBCZWIyPQCIxp3rSys6IjlJ%$u9B4N~!JV*iRbJ}MrBgFV4+1~ohH`O;%R=TB> zJ&kv>z>JsrT#bUREmsX!K0jfz z9|%wfJ-od}T%;mz_{z$l$5mf&hLitgiQQ{dMxEb|`PCX~Ds{@su~Y z*!}piP6lzC;zcy1h$}zbNzaW)VFIdp4PYoUY(^j zF8-a2+e|cswzT<|O{tHhd&4)KLx2&8F=Op{iBoAIg`xrN7w6CX6kKx}NO@k9 zz6=UDLA?B9c&Bc4ur0L=v%5{~F$95Mux@7VVo+;1YHoItDeU+3yPGu0=dCitwjnn2 z3x1Si0c!)UIc#GM-$#H@;e4rm_~LL4LcP0bC3kkfZl%H#p?_v@D5$Q4Y2qa-jW2l&3a^5YI=>~}g4I92aL06kX+_`^Vn zReA=FfSyiD1_=VC#c25D@;vYmkyNLFBbYR+BFJ6=hb7J_o1}tUo5U3GBzb2#?6bR% z>4)je-*Tuj2|b*4Bl#Mlt)6d5>WC$sP(0$FcjZGvg8qxABl?c*AeXjSb&=|1QylUi zRDfNZ;HEuLIafkL0s7kKJv82Rj@RN6v4Hxi4f^XSQYT>lXX(l?eBsvW`(LHJ!~9jC z2Tcxur!j#0PmvFVZnaXr81j9Xq&UN@ETh#8A<8#whaP~C03dr>V`F}gIRMX6H_Sfp zhwAww@ZG>M@5WP5xf*z0Gr;)K;Txa}RI z_)zSw{AWFLQ$_A0x5a7)Nj-?L6O;f#tQYopRBg|mNAGT18OFK^La}4D0gxB!uJ>2| z&WO&>bs0PBc4S6{0pw1@b&vJ>U%_UVlnP#1=mI4)X3q1mxwzrGyn+0sUCvTa77WaS zvE=iGq?f_h{nkQP1ikAS`TLeET@6AXZe6Wvd|c|Uu1tA;2jyD@Xf7zTEHPdBzbD$- zX69t61d5=*26E(haY7zM%bk(6+Ufx$V7Q4Nro{{!U+S52M&X1cvc-}Wdhnl+9efCS z+K5DGA3||W{Nrj2Bgx?F=oR(4gK1UIpWip1)ZI=|tBv8UOo`KGIx%Gr(Yp_DP=3=} z7}39gC)*5s729FMKYQgJmrTGtS6T(ykltb0~5b&MkS!R#0g(x?iR5E zr^o38K1CH+byJ1dh}A98+}V|caaR8aX^6TtEPBE-RKA+kJQBd)+wUwpuWf_w;m`!)jV1-({(e^0Z?MVjwzIgTv=9_{1~kFhKNKQC93}=b%wmbJ zF22!?J^~p#*RQ{L8h1igy8vQQ(TMEZ0{5)fMG}iw-29ZDY)`+Mo2e2U(m5MZ3DziO zB;2|}(p8KOP!S;B5XrK`{roWQ<*lS7CDRlop4+3hMq&^0At(&<^nm~MVX+gztB1eA zc>#!sp?agO)^}&QSST=epMh}()S;ka%2Lodv7&fjv_!gkLjQt=Rd=E|gfRa`Tz6w~ z*K9t8@__j_Qcg|_C=>pKV+KIASi!bz^m|BSL^NAyP=T~)ObAeup`*Y>*gwJ~#of9# zV%BEhdyHGSKJR7Pxr_{m>38mxYv!#^gJ6u<0-<1H}UuSdXJh)kml#6$o?<=;8s`~{X?YQ4UQVcsEp!%cCVO&0!+Ag@V zwHkP{Y0ya}p!gE_>Md~A;dmtCjwkN$RzBRaJpML(swETLH8A<9G12=il)@Ij9HUG! zi8YWi*>G2Pt-Y@|dhH4O1lW0CF2PmcgPu z5p~5&k-Q}UA$Bqq4i$-}W4h`4jqNuyd#q!A1~&;Lh?NSx=OtW_lJK6h&|UnnbU1*z zSXEsfo4TGV#^L?u1rG)2eG2UsGAZ?7h313tK3vAyyjy+s{`ojgj7nN-W$m#-y zE;cqA)P0djP(EjA>E+?^_#VTMWToy>eg563Yafv}>lIzwpbb1+#MHw;4}Yls8;m^e z%q)_bk8d;Jbjf3QeC`RXx|H$SdDyr_KtjSW=;}{?)F!J6V=+p=gDFG?6WDr6RhFDa zdi*co1x&Y*nzKXdGgqhEGvq<^N>pz{wmGhIo0QSL@aZl-+2t=_> zu?!J9^ejRf*q4Eh26vYa4kyxV+y@~)>Nho6)hl>#jC(UY)9%dTo@TlV=E7A3Gx#|m+INUn|4Nw#8^YHG zKbO74(Vj=>?M`=6WeE05_7b=C-D!p>T-{rktA2O`GI8-ZsPN=1X#so#F;gzc!!6eQ zxn4gHsA}BgIBZhLAvH2VAkgNEt+am*EnsqE*9U;b;}4d#$ePsDQ|z!hBI9=05Q@+H zeK66w|ZcAmR#)A~hWo)W(T|Dd}IuKyvxZw%!4ZYjqCv9GzygFbqfzJ(~MksFrSj zm#i2SW**h8fx6?4w>Xm`UvVvsQR=tfEIIbsy%S&np~^5(mRQdRoG!-@tBw-PTCc8k zS;NuUU+|xBs%`%?V))&haci1K*+780vIuC%F&S`@YEL+Ios0qx_1h+inJQV*h{!t! z2t9BBKG4ql`VwdJ)?O5jZe5H!{XY=o4+KH7v(Z*(q_ByWtwFhU-Jmo!y%e;Ri!&QP zyJGQ#A(J2d9tH`pFh%9s;F9h%Te#3H2z=5R8$313a;8vvXnImZi@c?nBHH%SG_SI^ zTEn1isD~W{wY9VFeZg#Yz`=uee88X1|CO@+#U_%9;TtjRgO^S|LN@Q#0I1mE^4YuT zos-QO&B>oHw5qw_`-(R|f;~4|N2=?#1hrrsWXA1AwoQK(lv*&q8$z0%BfQ?KvDX;v z9Ay%Xkl~cAq9NGyOz{RCgkvW7dfIL0QtwHK5-uW+8E~VUJSxlY#qb@M0-T#!Qf0dx z+@gat^+CgV*Vs_)8^_9(Di19XGY#?x4SeBq^`}c$(nua5+1c}M;nkNY>W8Q=CvwfN zW)dcN3jYhA+94XCl4hP8w>cX$w$)9xh3Wv1UCIA^3pKnhps{(twEFOeNzlQgL&Ie1sSF6s9Ku1UTThz8#b02y^>zMVp1{^>}ytWCA`eV%&8S_ zJo+vZ7Cz_ysHm9euYmvPY7N8lLrcK77;a+Ur8=Mn7V+zJq*e!2*LMtM+zwjp+_*LX zwL?6#gTt;Nw+EQSeKb?aNd*Ys+oMG%dnI>H?o{!o|LS=(YQ7Y{jwzC#h8qB)18V?Q zyTf0~#ONa6fygeV)Q}>z7UIq1xGxwIQuaz3h&GE-(fF zME##mRlc{J@&PfvJGy(?D!1iHiiy(<)GAhXLB&LYdqZz%5t%ZW>}oUr{GgHw)bc#eTaUlREMXaRtD$qt@ zD=Lt~N<%6gQ|Bn%v`03HN>D?}8uEEX1JGC)?k zbH5bn8tg$A4pdO~3~as5S*((y+7oIHPom z*VYIyZ@ST#J8HnTidrA=h4Ts91FlF(9Deo5qto9f*8NAZY@j8~FCDVsc2!!BMlh<`vUMqVe1eaf_yFYxLj#d%Y!s9|NcC z!%No<-MLkiiuh?yY+3qe(EvoQB+5x3-R+b&uoExg;nROvC8cjb3lvEEfhnpE1p6v+ zt>N?cFllRuqjh8i+P$c+w;!uNy43@jOUiiXmi6)R@y0+X7I5)j+`1mIuD8S7Ej299 z-CvDhMlrmd8shW}yJD*!!5ssq+8xEl>LZxj3cmP5dRIZwz@hP@YO>Uk7=sV-~; zFp(zA{w^5BU6&?UL|%&UBdVpKIb(Hmo&qx?45E5Y%7SFQqjW+vbT)2Np~SsbSI>U~2XTD%iO4y-+~_%S%#?QC z5yPfMEL5C;hopeWXSSbjdu}WApiRKlg2w10!P(-rAKdU4`9wcinp;P;E^7i=eWzk3 zdQ`{&&zzp6D30aM1OdA)>_fx)G(zuz&VMG$> zl>=mDih2aTaKVUDGc1r*F?LDAy2qN9^=9W}HBEHeeVkS_6PG>+vw7?mNPdLMA>5ya zc|1y5={`{>z@_Z0*M2njd7;Q|Pdq7&r)=a_(@TmbR;< zG&lva^6QMuS+8~J?IfUn6se70b*UZCNX*;E*)d(JxTgnrevREt+T{PtOH?kp8T4xGRay5e| zVluXPN%Xo^3E_bh{6CB?&i40vW(O6kq4F0mU#<%LN+j`>v>z24m$T`+R*yef(5d>V zv)NwfI-~5)-;b0(Qjz?9*K@VoZ!tz)g)ihj9lI(;e1A{jjb}Tyetdae$ylb{sC`L>VoxAMal3{b*WFz6mc$7%MT?LJ|Y4W~TVkvIz;BIBHtK|M+80LugL#`TJdYVT1 zqz<%vseSQhebQ}K#GzXyb!!tYD_y=sQA`~zHqnA573X+X5nSuUKagvU1y`h(bQ4O_ zNM6+>XKNETYx@`LOyAkm{B`e;@Z1~=VbCMPd0Ok}I;5pE5t~tw-s8pnmrPrGJGO80 z`@`o+JR|b%2u#&2kM0F^S91(@D;os-Un2be!V~I*s5hD(IeToUlgB>YB(STibCpWm z#>^t8L6aCb_JbS(kBs9q0vdg|tRdpvpEkuk=EXg8whw-xr{>#kfL?17fb6Qz`rr-6 z?!s^QP)*-BjXi##jytXDe3L%n_m9?=7OxooUZL&W944&d?by~N$BTN&64D(f9(r!j zqQNhqI1fS5c#_`N+F%VbLk{l+d;Me{!ZJ(;S60H(Gk}P>dMu-lSlV>*j4^jOJnHjx z$(1qYX3xnfaCAfYUZffy`nt6AP(Xlp(Fr$u8qtD*!Z}jiA`(jT zmX`V2nwKzlL;Nk3m8XcilDuXOy^FxP;8f;C3CU2#Al*@5)n`?YK&vKq7&fXBQ!C=oHL$a)vnlT|zd0=!@ zlT_8+U24#m4tv zfS29Ra@Nt1-69d+@!WZ#>}FQpl1azgWehK@au9aKVs6UiLkCDS*~~`tNyL19DY-2Z zLdREcz7sc=H>CCk)4KerP03fUg@>EHQgZ<>z7Ih@cGz;_;-}m>PPC6NLM*`dI6@{p zplqMp43~CeH#VJY0uGrO>>|!uS`|1AKY!`yVqO+|NvxkX5HCJ7pXyYaqaR+#-uvs) zY*AhtO0e-ZO2i(B*_>z9|cV4e@;lGGv~8vm^vGRU#T0#oA1$i!NL zFpqKGB5tLfHHTT*d}|yMLUn?=m8iAta^*sA6CR7m8p=~vC|ft8EUA$4!=8NBoYru8 z$J?=;FI@Bn4b?&^0!n!K*eW=^yHv2)xsV_vq9gj;qyt8@Y%hGxYjF!NcHS7Au8U^m zW@cszNH{;$OC#p?FLug8l5R#4$!$325+&t*tUn`GI{ayWkGOw4Bt0W*OI4F(jMD|| zKux!+snN^dAnL(dF68LgVm5dX>U{{>mz3uXk&}vPycoaZQc9F zhfJo)vqhKojW#PxlbE*XA?rF8JUK;-P#wbJU({oso13&Qc=GtJ47YYNQMsz7CUdNA zD_C4Gb9aA(G(jE<+ecmO`u%Oko9Mqb!#Nn|+@+MQb6bij^;zIvn#UWLLEL*j+JG`& z=-q3u;Gf9~QFKUoZyQC6`j{ZI^7)n2G-zG%qdLVJ(|i2AJw2aLe4+TbiKK0IJ6QJ| zt1Rd3xo8XfZw&BfkMB#e6U7|NaK@|0^m6Ao!0hI5TH0D8o7w)_sI06O1w-_t4O$t> zb}tc6;4L@{IeB5e*wfP!;5*q)Wki7;K?oqxnb+p0ebp63pGmUct2zDsG1VXir`x~vah6P+o`fd=o;+R*%!vys%bGB%;~Di z%1Y)j5bRRhzHm;VEXS(A#w>uTRH(hBp?N&JH5Si3)+YEg4d<%2 zNwD*9ud&TR|0>7d{zcj3lcZv71~D$ygcnN1jdv=P4O8)-e3@+NjGa!03`T}ZEwKCS zZbM1*M6`+-rg2*jWO z0+EN(Py=V|?4&TjA4(53t$Q@U@Takj297yAZy0$R!0kPKtlaHD4z6$)yDJ_x?sj&r z9*%I&bqbU+aMKmiP3rD;R-O;xu6*|%y4ZmX?QHqPrTKKN-1#KMC8hbqCFP~01~6j9T{n8 zFT6~+RGNINQ5TM6VUOk#Qq|-WWj-}~igqC4|GVjG(k_+MKlC2O#yZtA!1mGa!rFn_)K5}+xH62rxWs=t5nBk3$$ zPU8RkMW#{;@qS>fTI=b5O(fX3m8ntHq_>D^WRv77|Bjp!(&_YXn{Y4LGfjV4(mg(J z5cTkvaHg35V>xud%aO&x=5Dor-TPS|2V!{pK}f^h1@^Z^Nk>D2Lp)_WBUknoiWg*P z{_~?CP|gEjp?uI@!t}D+<Ui8Vnjs>$npEV#Hb`(b%+B_-~D5n*Plm&o#ySq zmKg4y=hNL7@4p|7A0<00YoIkejgjJU#&G<3q>(@p)VrAeTw;bGqZ0j}D^)VUJaV{o z%kpv^bkB|T_m}^<7W|XzR$2efDUfdJtxdN?B}QeBphN>kWyqgfs^o$7Qsi}-Kx^U% zGiiS=sKQ+V@wI&rA|Bw;6k2*aGu3}CHqN2}d4+!vS|M)Z0?}vx((`3q;0on6@;^5- z#N`UnyNHpw3Fap%X4vZU{t`%h-(L%#A_-*3B*p|9SJcSx=h2*&9;U{RK9@Qh*it?C zIy>1?|I(RLW;!(ZAD2s=2W+puoPufoc?<-IB@#pww;U5QMHE^8TpZ>Eoa2%%;2baG zp{FYUG96VE>9Hlp#MLW3${Dum+U0+QWO;>I0rctnz47WH{-stX4FTUjZww9uH2q00 zJy(5XhWxMhHRb@$`Kh;5NWpk&2AIZ`^*_&m!fpX`zhs~l_qMHwPGd08^UrUA!ZbwZEP^;`avKfBE4@)lhEN>R$o6UlCZ;qkHs!``$5W#%-lS6BFjME^+6_ z#sI7O?+~{HT=1j#%X!U5Q#iM)opFHq|91qFNsjN3gSrT?2V(+X*XXFx#L8cOVF-YJ zr{4K_+qIgNVjUeF+ugOvv09&!zw3HBpj>hK_A*yJ%uV zGdtM$SfMDDA5({GOb|VSf7jkvxt4sT2-*ir@SpPua-cfnCjv|);WZ7khVoAxjr{gJ zUYK{!(r>H1EeWDLI(5jqF7ZmS-zGjHA~suL1ht=+*BPdy78Vh~%UcHTX;wRr2%z5D z>a>a935eS8P*RT4PD#{24NgNvx%4(0=odDJf(|#IcGo77C;{C_CbK^rL-0S3CTr%8 zA)ggajv$|5Dq82yBi6(}BNIvkdE9ujHF>JO9acc9ET-}nuAMyd=!|JUkPj*xA=`b% zp41+<>vCLXS~oha8Iw+~q4J!${T6Irs2A^EF!kG&VBcaL|l zK1CMO9`U)_DU#mD{y_`VK`-}@6m3xq>M5djbt4Yq3h5b&1E_s^!+i#Ohop8QENBdi z9iOyu6@60oQ+)?{GX@HBy{)1iCHh~ErtuQ;p@;jf(v{xnWVDBc-&T_CT>gBPUy6VA zIv5Re)mbw;kb3XdSYNBrr@qE6Dx{x*TRAM<0)$1+o@j8Cj=C%*wYnxQm6U;~tKSC! zWe_w)XwRB|1BdULAw5+v55Wr29$)G4LE>yv3- z{BtYdh%moYa8RR{mtSDm*DyHPIe0`*cK#0w+Y8kT*!grZ z=>wxuibm=8%zp%IEH0CQn@&1JM2%UCj>&&r%ZM_2_JX_3R9Q)w>KY**oaP3Zb6t&Xzo95C;1QWk0!^hD!D?4@nbL z@0>A7nl`qzhbiwJKoX~keO%c?0oW*S;h>{(ZIpw(vfROX=ZQ3{67U!%QzxN|`SDeXSua93x<{(O17 zj1=5f_6g?I{Bio!{+6G&_i@0J`FHkeQEyp!(I}^-5vEnmuBVedkQ$rSsmP;I854=Y3X955Lf}C(Wridk<68BD&Mp zxz$|VvGdnAoxt+b+kv}m;B4WWi2)NyCjp}S-5c`*kxbw8<9r(K9IsVE%hr0c)ASoQ zbvC0;CcEo;<}$-JQB#7{zCZmpi6=uk!Q#q^ik}ts=bOG-)CM?hM$C1lRnODMPwv$T zja7*5Ka2N1MtC3hOxrjM$yL>}%4K9~ALr&iu}Oh^o37RDe<8GhP3(hR{iFc@fV6g& z9jm;ukKVvyo4kNbW_p9rpR0}kt*(BD6^$el*g2DtFZHy@rvO(cZPjAr?$(|j6yz!@ zw{a`T;c#yuuhXx>lc^Xc?Q!I|0NTvGf%VEnjqX>hwR6f}M)?_RYN(X%iB`f_4+Aay zM4#;0N^QAL{*e0-@Lt0o&#QkfXj7%9d!j~kf4jc3Npj=B$NQQqgX zk49%pGBa1YpCIJ-w@P4A>yt^H*#Wj2dwg1fzRLTD8(8x2%#|el$uFKbx2?AME@6e~ zOD8`KV9H`khbWBjn&|<7*UV8=Q8RIMB{6>Tgm_3 zMs~mYZfVQ>^)e^*&DKvnDn8Q{?<}&jbh8}sn1gv=Ks?q`)2X_8^@#mG#-2JagH3Ip zx~+xu_9TT$;l6CGV?rm^-jzpR`Cx5+PP^NGB!B)>pOA&@0D67z*sOE<`0#s4(C*ND zJZji9*sXndUO(s~t71l4z={X#xvxlx56RIx~qJ}9^u*vWckRP-;NvgB|@366bnvU6zIjk6uOBBCIr zGfO680i34ZCnfy{~0MOfmZq@0quC)4pWWuL1AxUNe?vNSLL+(qkIv z+y5#}$RV-Nzk&>4h?7`5UDA`h@?7BLhLv7sWj1D;^G?8yfk3s*i?DeUz&bsTI-VV6 zR(iehI4iGZp1#zLa5?{^EJXbPSQ7Z>bfwqQE)cyGH}5V4?=o^u9G~DOeS9;9GIviZ zhx}4pygJ>JB1%h}ERm&6=T&JEK(tEy>ESr#^sy|;^jA{* z8B5hAsL^gOYM&0-5zLQ>bHg2iJ!mPxzBG=pf_IkBlyF}iWoN#3F&#~+C zLgNtm@3iqL97`JJ0_X-BQJ?ZVJUMy1Q}08CzjcT6B)*wh9>WinueK*kx0EQ0vm-8O zMFo{FEzofP@NA-wI$Wo^-)Om{le)s+KSQIKI!kl6%0{wdMpy0hyijVr-L>n$XpL-U z5)fd`z+D4_sdz|du3v8x>HcQD=;YJyJ;0gWrm?-ts%-1gY^^K(IaO)@vUN_jxPJPa z)5l!7j)J10;qdnb#WzwgcSlL@tCJssducw4cwjklU-kUP;i53^7RHYO3t zC&Z-N#@}XeQmlv+21YS%Yd;V95`i4<*?QMz#9Lz6Y_aot$uQa3#S-F=7fcjLj-<}_Hz`EbIrq}bso?uMgv2GS0u95FgECl(iu7p3i6)%VOm_!_)<{G zwoz3srE+b5U^muy@2lVKskI=~*oWcB{b!jniwez*4<*F?8M4M5G9BRp!M8KWvopXq zT=n{Wwv~R^N093v=?!I@!6wT^4pJ=2Zruu9EvulSfRNRpVTXVt^2g<2XIZCUI@V_F zrB~{6&7YE{5*@DQD|=a1(DSIJIrsBb&!hHX7HWr4)Cmi9_u88E9AuqoJdyjfH}i{& z3-{>dWiR0Qel3Z7LzR4(%UVES?E;Q;rb3`4M~I@gtAckB?Ueb5*YRO#0=M1yc|HOD zJY*Q~I~@-%NuI)r(X4U`2;|t(6S$A!K`QQ9({;xwqkr$DG{Z_55f{F@bA&KB3obZ*}zayvxbq zbG#Py`nA5eZ0dCl4cZ3}#7=RHUAudi!^-N2Y`v&4Oq2Nv84u4wz z{F7|>(VY6k^b_b;ezYSm`|R=g?VZLZid>5pGL_-}iIo%T-KnYmK@Ov>@0d5!4qNlT#|oI}@T(Hyl5x9#6lKkDrZ zk&?uXJVvsa%RA>=mfzsqM zpFq;fRLY1OQ|$zZ`c3xF+nj6JizX+kw{*haJjh+iP5|97u*^fDYHBg~T;`qiNOka0 zc1yPIn$o1(g>Vas;4B{5)3eABlA6L>uVReevrE`blA#$}$>9{dH@Nt3FwouW2h_}Z z?;aZK9u}tJ?w*y4#9tE->^V7i`~Lm>#;|CuY;Xg3UT=2f!Zyj;PKghQcxYYL68>%` zp+dV;0mN1NP%;sZnePG}o~(3kl+4E~6r;YaC*~sVGdnksjpt8;@J1YppS!xtCm)Mm z?yG>D$A?Q#sw1ukdGDR(@6JGlHJohGaW z`K}4gNVDc@@_y~J9vu(2#E3@hGG&cgJq=*;v_;!S7j&2im*#DgGRXI-a+flb8L0S| zSL-61o0)g?LqnP2JG zPuT*l0E}QZ+4qoZ77@_%H6SBKbOf8b+wIY7t?!dAE@Bdrwk}6RKq!Uqw+#%`Z`_~? z3#(DS*$NjvH9_zMDOx((0G8%><#|HRSVeor> zv_97*uQQF~bLU)Xr&Cz;22B6O;5}zbTVd62v}pE}*L2nU*pc~X$@e$T&-xLmPBX>w+IkJNW`B5v39uw#kN&0sFpVaL zUsxEd8UlXt!Mby?eFPZ_L6K*v=l)s^?+u&!$u~g6OJ$Zm$en;*pMNVQMNjuEbmWuc zeK&+$ck09G!R^Q=CG}|dD+o8FZ{$0J^bpqg38LZEnfJ=>p{y`9uetf42Tq@Om4plG zzr5U81}p*y8NbGh1UaP^CLim7$|I)J?##4rl9U!P=#p{|<#+FVSfK&r)0BA9%q~8n z#rH49v-y(}!Nw)>=$50OX#xVm0>8soMn#ziABxYno{o+rF_DRYKGh6S_y~QWc|P&U z{LKFAcr};jW8PU=CHohCWN4xg@0CNg(67^bRI-KhTfo1}j`Yu|(*=g3GkO@m3mCpr zKX7Rf(M?pQGg=uzB zU0S?t7Qp!OWi~CMzv&tvticRdKa!jt1GBu6`pdGqU#C%}@l1(BH2c!#5H~5(N+mp7 zg>SR-=6v{LU#`6i_N8eHq))x{JL1SsYF4X-mg)QF$#KaSRYueIlmm z_C48_J7kMXU)?@OH4wapso@mg1)4dY#?Cs*?xg=*St(-NYWmU7T$jbj@2gC*`xgfH ze5b`@yv$lFwj&W20mCye(4jnC00d>Ajw0aAU8fVqva|-=TKspv99xZgd2W~I_H1h1 zaZ`^W8hgsl3%AVKVG%bYTK47K^3t>J%!rFI$_yEC75Z>4S6+ey)_e=p8R0`$LU|_V zf>eT+9^+?)S63#(@Qr#NxlvV`dpM3c3P>-tMxnV0XLmTHE&>WdL}6wok9XappP%LR zKFb*b&9kVD7Eeu~gK*&3S*V{mH)N>`V%6AAiMI#eZWY!mLbgyfKEjB0PtO7fqT?-< zA7kol;pWu^me07V=|bOM)@42RwvTxX%l_<$W&atIyxghdwS4s zj*AIb9c2*nYfsk4f?eYJdP^C}7^prLu=Bv$M~0g3gb9o9e=q5DR>}S`LWL@6!u-mp z(H)(7R$vyn)z%wo*G?r%r)O8Tw)hn(g<%nGH;uSL*+;imprJ}VdD)CEuk@dl%20|S z#|nOY2kWm&jYvsTE4vK#u_zl^kolligT#W9&sH7j>?QYL{eur&t31NeKx#Uarluej zqnU;&n5~OIPyuz;=t__ZQs&!<+dJZGLAU+^NIcgvJJj_E2x2W$6>(%Dc+1eqA}|w0 zi@h4t6oQGNrQwW-sZ~vOba+NH({UB65q%-K0L2e=D?l)`w*6!|g}8~U(q_WRPWnEMBi{PG;#;^_{otMb478y%Hq}8^16Db;dJY5*g%I6U;|Mlng*YZ`O9#`Z; zL3?7)rN|}MVk78^+UA0GL2O%^sWL&Sa z6C3|ohO*CRP)hmKU7ML|is6_^KgK$-GrY9y*rxV{s*<1QnpEN%1^v3WDK6+l0`=hQ zpoVnD1Hkfb$sO7zr3LP5;pgaATfiEAGkvv1J@e8AEEu zfXt~UPp6O(tq@WhlFGLYRJ*MXAx!d(Kj;;blMj=-yPtISFKVy0+xp&1?Rr>)dGM!QJ8Hr}8Yll>NK&g;ibH74O>@Pq*8*z5Dj7a;r75KJKlKB^110yde++U=%dwr^|ErFSNW+!;QRS({*5VLF(mx4fA# z1P`nU$jQxZr&COoRO$^FZOSbLA3s87n{_lb-AhmhBDhfSX>a^crYdf6!7`kiREchA ziH9Kof*Hu7BdIOC`#zGZ^A_<+Jvh&5Lr}(6(4ljCXmfcyLp(fj(ajC zly{ZAP=Rrc#t`A)z=DR@pm+R`+Wfe== znK%$Z!YZ`I*^qLjI+)3j72ztg8cjBj#_Y?lt)gAtDmnGM$L3V=DQUDyLN`pf3Q=W0 z0=w7p@OeJnR6J+iwixz#TX;~4Jd&S@Xt6&ycjH09b}hY8H+MZDC%+4jR)Xv}yx0KM zOEx+!j~G;|^Qx)soHzsMrnrZ=oUg{+pc!4(eC|Bl>sL`)3iu7IsqSkN6o6WFbocvz z0|u0S5UQuMls_T)-pz+glh-w1)O8~lS$$=}(Gd5(@{n-8T~p3CSuxkvE(*JH;YBcV zrxCJaFO${W-Q9@qs`exA=k!=$s@FgBr`qqSNMKV`pZ35i@|WB8zPT@oAM!%7vc9|_ zmsi85XxiD~iTD3etvzl&O^U80B&%v%=!NjEo(ZGNlK-Oa85eTXT*Is zBr@5N22y@d|LDC%ljB~FEZg`&d=%&1H~dPy2T$z4b$4C!E!;m79PBFwvj={$IYV!n zF?Q0Y z=MOy@Uq~IPtiG`c1Pe-J!Cbt(y(JYDaXuvyximb{(IOi784QQG_1>eW-y;%Ehpvd8 zNmfhjft8Y%UYsh(${jtc627WZ+XYcKbg)E>D>?03Ei$O;!!Laco34DrEl-H|{VgjN zIY!%7wU8*rpBjF--}}kPmr952=hf18xzqiMdREw|4|;SXhW6+D*yWWLj_;4&wj*2} zfa_f{g~9zH3t2t&`0E^K)ZmG^Wu|!$5XDAG3FMWsZxMIaIQ;x?BFO{^ep=?Dk&x47hMN91}FmB zMo+lHL?VQ&MN+SUQ){fi4cjJFL|08X6XDkNdE1d=v&DMOxa#UN^Z09vYckVP&dd`* zXL#st>%*CNBiD*CJC{``%>Z-z7wcMo+m?-v3l^kC<-X(q@AEJXI4*}=qBxSAvs_{z zn(Nlz=Vb*B0M9c@b5hAKAinBR7J&C1F=Ouf!PwT(%Zbs2m8vH zhTA2Y{|Op~QnUQ9$A?agleb+KE0lebMFIE`isRjM z9&k!u=#~e14CqoA9|MbHhGjoSedUtxTVq;;+j^YNY4 zAl~3gC!jVM9U)feO8J3}*I)|KRW#oH zWQE9GUp6JUVA!tdS>C76X7tHY-3&Z$dWZ{L`A^S5S=d~JFUOvTm-`J#E^2#*TegSSUN~P^8H?zoQ zfxNJ~zh{{gqHGz#ys3x|?jN<;X``x@PHiBi;rY|~=_G;>82%oJNgR?KDC58WfXGEh z7rlKe)ZE-0I$jRcRWmd1b9T1J%69pB`(y43xIda;r!{$l8IXZArOeiVn2VSw2uw2##AN0ovMS54jM3o=W`KJ(%w2?4PD)xg?yEp%Wod|lMMv8 zVioSYw(viYR_>XZ8PmWqySc1~mTn2PfkcxO3wFmQM!+gvAR1|E#+>O6YwbT7q@&U{Z-ucxDpEYn;}^IqQZ80Dg!ytd}_X5sMK zo|VFB#?(Y-u^zumAe0^xMgUUSYW20WsE6!w@QB2~z<_C)cae5I3Y9%FTmr_+x82F! z)0v!{MEgw#fLgzP-RQG8eAC6Pq@;9sJmptE9FW%Hsso3Mp@>K8WYN!`|I|J?C=ulk zDJ~Xm*e`;UB_t#?img>U-1TbT3Y<%yrsPvr&N|tBW})+Ott&Mvi>KlEIUF>+-Zg^S zk*>6W=-VI=e)|U_C?-`~TOr=sS-KRt10u1#nPII>r!Z)Hv&#&7_UzfJbnrU2~2JwPW1Kb`;wBU zpvi&Cev5-{tAnm^AI(C|bN-F!rPa(yGluxsQOGEiHh_OrvtIZVA`A^Xtz`Eo{i#)y zSE-vtsOw`AgpnKjDSR!zC*LdhBa@?~?`wDSQ3tTt&WK&cB%_fV&f4(z zDS*lg(%!$nKu1q+X3l%|Y|fiE&EBz<2tKT)rluv~<3FM{H8r(kNGl53jg3O{`tb^; z(YU3xHS9W<3^Olp-whs;32ba^_|GS5UwDlit1l{gPCVHb2Hm}Tcdwu?aM+Hi{pgpb44lqr)b~#(O(vK4b~6UbX259@HUVqu=*-h+pVW1w0(P}VY~ck~gxL}EZ>nJOh1!^`uVEVo60WKFD^^Yi z5~~jS`h}PQh>(M-`XU*aWjqH@|SaO>nNlbK!HoR^VW^Mzcm^ zy@viUV5^LWN(%okHDu-H_Goeqi8HV`FZxaf6Yz+0<->c0W=y|jqhCx$a{jGRE3-m2 zS2zDNfI&RIpcxr!wEN|ox9lT)`U+L&u>BLCqe}_^nT9wc^gwu2VfT_|nT(l2-2+Ck zl$JZ{TtDIFpvvTNF!M)wj3IBMN?hua&mei#kUFaJ)66?}r@5M#{uU}Zx3S9*tEjj+ zuAjOQklwz>yxwlU1=QY9=|OrvF_!!ZG>zrKE2`g_@dYhVkH|@XZEa1+&R*X{SXl7> z^UpsOHg!W35*oK|(TRvwS(?@Zx`It3=!1ct!TZHVGm=r268Q_M$^r6~X#esq?&r^+ zAMU@3m~=sI!jQFG1}28>kU%`er>vJ>eNaTR5xI;uTRXdr zdRm+1<>kGGsDs8vkV&QM&k!&#W#RM1$^fjCXn?V?u`i|xTtBSTGcZ2>Et|(T_{WcX z%6=0r6<&>Yv4T2Q@;K)AatH*%cWylhT$nT_OnnJN4F+En6WcY0%yaj8v9Jv4#UsPY zldkNMHf#*fojYf1Z%?g=7iVi>(n+I3eUj5)hf#C$UI-bLu9%Z$Z6eE4uCa{%G0 z$CQ2WqrepVzWBq8SkOMbrAu8yU~}s0*PL1S+u-*fihjljXCd2c9XyT*Bl;hihOw*d z8ttdq*|&<|fgYwu{kiJst!EY>ai`(SYkR|$rdS}gh^wF$cu0=R+J2gi?ePNCC-zfH zO3GGw_6fRz>9+ZuroO-(DJLB(exIo)1$|x`s<{mfSsJ{448dtq4(@}`VR7ks4Y?s2 zya7Kx_N6xI!Y1d-nBX>?oSeS4pOtOe7+k%jq9)I_%RdL7PfRqbc7M0R4TaY2W78{a zpKiAO%!YT4cycOIn;NgP6*_ZY4Xzp)Jv9-&ME%5*nIXR3`v(3ri;0`6rO z^+Hak17A)?jpy|A=kIIN6+Pct>%J8NS)L)>a+L0e->36;&mxSO6@7tZp}{L6-P^=w zfxRF8nqTNCKSS3Y1i}FtXXfq*t65v!9omwAQfZY;6*-kP%V~L&6(S%y{x(%^S505= z%pD*Wf~#}Fw(7D%+42v5=kw@joolqTv_j|30e+>hvxUQLfYm*{yq*;5bF=dD>g(zC zRv~|4${?TwT`Yru#9FUC9$NGkS;4 zb)~XNA1k#2C$peXgL_6D!pa-8Dat?D*c6Gl@(POKV>X3HDy73s)Sdv*B zZ>F>l?c&B-N`khy8V}454bT5DYfDbXzbx^$^RF+AwKzE#sqhLeE0a8S^3>7NqP55r zZ>v@gI`%(a{bb>lX0tw3f4Gb~?(&W`o0QAA{m(yN4fItQRRaT+N6h?ItK{Oi<(iZ9 zm8ewB&3Urx*5p&Xe7WWZxrc@n_ve#9^H}WW2mL^Iw7hN<^!xYkveP|4Z1VlMyR+l| zwr2dmzqN*NRYvAjU0vN{58qEj$+m2{47e;QaliPmx()0mrGIMz1KflEnOH8KZ{Hep z4F)4fWprV?Eu}mzCkG%BDW!0D)63`r6YkaoxrhDzR8Wd*i!bQ_emRFtp5ZuX1b0u< zd+Vg9+#u(}$an_Y_5C#No{@Y@fJ#)D3l?E+OzA|YxJ%4-LFNsdn1B6%U){1C@FYs0 zCaCq-!(=G>c3!BhXq7RB{HGUS3>^V|YJfSC2atiwWf+U^-mJBeBn4CDbI4hsjiM-E znEGhb`^1l|@Cv{+%c7MV)?2;yZ0sQg=q)qR^^b-wr7#|YnYc0VAR-s2 z+@TNqO{9d|P{kL|*Qat)=Q8OU>yc^+G@+yY*6Tr+jXy^R9WMlVr`fc}K@X32QI*iS zA^_1rR1OoSkATWA;|VtHunToaFRqMn+rwLB`K`${%BLMIe=6aDMOD^RN&u+Rd7@%9 zyqU?HfSdOm#-^N_{IM#DRchx>OS^1R;q1&Po!7U*J%vBB=4J>W{fy=FPBIK zLV7t{<0H$V#f1;d{=jyp?Ok%H@B0t?ls|t~N?c7oov<$~cyWvGT?$&=vw0x6yM&}z zDtVk+&D5+ojPX<+ZiQ%4m{g%lFa{Kds(y&vpmBaLIkNuLxv+b=sQLS)?GpAz!<6PBk3!2Z1+ekVhUA{#OP~TwNonTbSaSlK z6!kZ0N6kcsIBcE6;oar#aU6i_%n~RH#oKGY+~x>BF}k1^f#s3n|GfnY*ycq6Ac_GI zk-UFk;95XHeb)->zGSaNn;9v(0R>P6e40sBPmk#tyBOfy`T3En6P12ImDGN?zg2w* z;NoSVHSg!U6mxO_wWr8od(ztpBNpqYPVHfiAbWF1LGwUZzEo|#q8@-N znr2HmF!2&c+k-c_wuHI7jcPnUbjjB}e_Tv-=L(JCVzYH`CPr!%t_Tdby1e^MpA?8k zKyf-RCwKsmlJ;4Znnzy#)@VHuyuCZ&{GQY&IBeKwZFv7`_N)~ z0vCi*jeyoo&WejcT}4AUHg-G;6&ziDtV<%bPE5KAbq{D|$if4z;Oi?38L`IzjWTUQ z=3%hfeu&z&4EmI&+SvZo%Bvxu$~x$oSM%X3gj5JvW7O(R^~2jEb`|VZ)Z7_RN7~*V zpik=eFt`U`rNILI0s#C1-z=17>;IUV(o6J5{0ufYdcMan&9RHQOIQezacb z&75CYD0iDtOOfODYFs&Mft8($m8t?Tv}qe|{L8ZubH5&^$rQO;+S>aa8p^YGr|bP- zB@G9cKnvMH%9T@yPhF`%mfq-Bhm`v7yDJ|p=}!!kmDu2x*BgkU5am5S&_bpUPvxXH z*I>S`jje5~H#(GxzH0lswi))4h{)W}6pQ?~Z^OGpYr9Esc<#MI)MZO|t0-1R9Zzp> zcT6K05C-)2Dkv8u8oK%2YXD#Q6)0L^?ZIdGMitWY14o-4TnK{zElwE;XtXI%K*U6g zpQw!Yq@U=(OID;ao9>q#jM(-fQjj#|!k4q}UW=mQxIIN(PYuf!>j*Z21r?uptNx_+ zi^SMHRHCPmJnJlaTSTi;k4a^m-ma(L2D7_T{4-(w=Wrq~T++k%iI)7~qS^&~|9ZiC zb5~SPIM4B%BCwy~gt3B4&7W&>`iYN!w6eQ?otVa;fO{5x})K6Ky>2)J$?Gr2x%G8#T^G=7ZA`!l>F*dP3(vF?=69kXilFwlbaEu9nzjX3U^7KqBWG1y}U;$x#YnJg|r z$tU10`A4sG3OYA0sQuC>Qk9CQa01!@uv(`)_pO zy|3UNy~(d>JIPUhNR2k8`yjFA6g7eAeLno*=Xw8iawC&P>kHXRzPrp5Ai z)lX!Cl{AWY^w*>8Dd0K?It5w9@@Zf*z^%u$BO1!6ud`?T@+}l%n0hyn>2Y3=XeRtV zO=}NRlcfMDwK~U!6y52U?m>_LtGM~_ckkZ4crk+*bkf$Q*NEr&Ldqu(b&QQUmzI{e z%zCHzFls~=+Ou~nt zjDVdnK-lhg2{AUJ)$^x{tFf;i69_9KTib*B6iDw?6Kr(d`8S%$Hr!^>cF;zDQmf*+scP4bgqK3aV3>Cv!z;8KtOWn;;#-x0fAYr2&i7N z;2x41Ii}*QL*37f;Snf!Zy+{T>(Cd z`26|m&iZs;2n86Fs^BB)f$ioXC1Nof^pJ3|0}xy4h-dSwP#K?!YaW>%0lCL|vc{{z%c4zo zB;|@p8x^}LMzS5i3+)qdl#4=JNkqc>O>hNa=(ydTaVLPCeHd0V#q>K#{}T( zl5Zj)f55pHzH5s?VeKA$O6`Cs7#fEREqd%y%&=ul3lfHAUTlV@kEsBRG&fqh0e31f zsf!15tZTGG!|j5M(y+tdHqYrq7hs7PjY?_@WqIiCOeMS;z#ddU#0n^bDtW zA{1aQ(Q>JXP5Bn)eVs5LO^EijXD z!ZU`jM9_nc_H`4K3?hCOfD&-wiptLZDi*7Ts)1FjyHcY87SUiAV-UiSZ&@ZA) zs;epu`0*qVeR{!Z^xALp?9g&N*j{@3_HF;@sHTa@MAb;flTWo=QVzWtkLSGCr*wg~ zG!WqbK-8`2E(L<~x2`TSAUKoVxN(DLrR&ud4_c7(C^7`_HZmlDR9{_wAX(h-chorn6FODNln)$K%T$eQG!le2k2`kBahC`6ia*&eLFLZhk@0VQu@ zK}183N>RV6qgdHA3J9=ql0m5$LF$_#NrOeozMD@@Zfs$Lk&*FpW#z=N@xnoK1bt^; zpHG?%fQ0V-^UoM5UyXioVt@JaC8+R0d8AaIB0wDgP;>#vT9laCXJYmPZ*GWs)B)KM zH(J`Vnz}Stu(jDGR{l7T(00TKLpOf>rx?Dia=bUk)2_JD$_l8SEO?~^l{NIqu(o@~ zCD!BU%`;K!joGgNZ5_pMzr?)ffkUSB2S9ZV;n4HL_0NHXKie2W!2{QJi&c2R#g<|5 zyMOM*U_3zcx!-#F?6V%Ia!`uKE)v#My~4q6RX;3c>tZQABqh^4ez~@>MQVrX0hj&m z+40NSNucTa#)c_UA58hd>qQPOGWPjq;f3cxlPt`OT%iOux7`V#3#hv`AJl+q4%7*N zp{turLHsJTS^MDu^|@RP#8=h*>UXdD=l=kj{R{h>6o&A7=0Gtg1Z<^u_Gy(vq&yjn zLcj*6^6H|XJkq0Lm(a?-AaQYLQKK1j-*%nAtQ4T0o>mu9NLey6nwpoCloaIUwKz?V$YHzF<|OTb_;b(DkOJvAAmHxdVTN^! z-MGJN7Z>k8FPQwQChPMiP?eSWReIGttpqUQ5ob#zur`qc8o0w=D8m72FbBc@Odi7SO9UeS*AOw7ET;yP9 z_dMNcWw_|a&=48Yw)0e3Sy@}p45>s1qA0*3(Kl+S9NYn_#D(7py&-_;-0u5{q7JAl zaFb4%G9LRsQ#=N4uvh!*uAxo>r-Dubl!;?~WzJ)gDRRf#1u7d;e(PjFz0t=FQN#m1 zFmPKz+1*sEIiJ~?C zt31J7zAC4Fdi=7}M~AytflU|>Q}`9`Pwm$mS?$~!Z}(9xkv=6_fl?rIPXWE``4)Pi zULUtJ2730i?z9In+-J6&B-{H5wm+~FZd`qav5`sNY8p>CIjZcTWImNwXg)359;jo+ z4zvYksmueNY{zx}gM@%#2{Q`hMl_qMI6wcl0}uH=^_;wh2~*UbrW5PFKjerLfvKjj zKafN8?z)Kt3*s%yEX)(fB;s{(ey7m_v3?EQb_H^~z&%#Wl;9o<4hKhBc~mg+?(! z0bp0egg@Ns^T6j27^6i>>JsV2>fF%S69BZO00aXC{;OEvi?7evNpZJ3V0W^;!es(f zb+j`fw^CScO2XlgpgjtJzNf;_TkMf*zq-s}SW@(hNVYr)T%pVnDXt2w_Gr(>Y&Fx1 z`4$3nT(zqJ&TaUC!;8$!RmrFV2?But)Twb1Ff^4yqu*Z3lUOm>rC-Sx_$R|1=(CA$ zp@vUr$CT>vdOuMbm-jlj&Gnf;Y7Nnej6XeIc#gBV1v5nFp=9u8W|q9_v*V%D*SvJX z#KBBj0A6JR_+%_0+t$St<@}0>@KXWUSACrHDb-&cP!ZMbEljXxD#5Co(*bz6|8q7>=U zr39sg-UPNHpg}!;{(U&vkoz51kRO2o}9@Cd?5Qth0}u*LO4AI`%ZWwr1_U?Xo|3NX39 zer==(Sel#b>g&h34kezRomNs(8f$bNu1b1wDUTqBRa-NYk!iG)oX%6f+fr!P{IP{U z*x)nZ(j@}}PDqcL$AP_j_nz`l1!m+8L&F`T5w_ar0L)p)2xs~_1F&z$!uHgXTA_`4 zI+QPoHNQJKWjFKJZV{n<)&3~rbISG{#l9!s96~14Zi_pl+>NAe`M`2|Iy>jTy@dL6tZdKHOwxSBh5P~) zCU&3!1*)_xo0>9H%0JcAl+eu%vE>EYpJN9GYc@%`S$AhC-M9kFYXHGS5#kAL?m|fS zH;$-1>=!qb_VNvO{n{{c==`yegUoY$qVMvfdlQDQN_{sDY_AyfTECs=@&h)ruoYMm zPo6k&ROU;fvmtqjSSa%+!v3_(FRlI(FA^1N-a~thlN-XdwZHxGV83H9kjGh(WOBgm z+qZ%Iy?OJ3rDeLSz{tlZ$Cp=cL1Flb2@XC!f`OWXg3nCTT-6d=US7A8D%I7Kojq2o zg>>o=y>%;>(;n#edbg4ZQwqbtSkhR@)_)QoKPJ-z-0R$T?%Z){0yjw*eK-O^kZFq7 zSJ(3LS}8l-hTUqm+`c#S`*J}b(b-M^=9)Zk^#!fuSiXbe)FInM+;)ub(xmQN3v=^U zuy*U*ym<%$98i)Z5^1cFy7~$dY98IqM=-0DQ9a}3Zj15^`rpk5>SQYgkvMhsHcEA$ zE#Al#`wo{IU6kNb9Gdni?&+6<{%Hgv46SS0SGwy?x4zgSA7BKWecfB&9jM_Z5ioye zuWB_`hxwS=VYd^Z*i*$qMdgQs76hO2eFJbf{s|{_!)~WQxxAl06lD|wZo_?VQd0PVZ;DxX*RNjH^zsnW#61h6>#L7cLWVs~0@F`?@;U15C79ykyaGc`3g=I$y& ze?HuXx~BvJI5LpP$8S#b)Wj-FyXl-gTi+X};5K;K$cP)bSbjZrtlp08k^oX*DK3~C z4)!rlRn4FKg_F~j07(a$hnBv+&ygkIFa10?=wceYJ{r}e_gn2sx9L!t{Vb2{yIE#> zGVoULs@QF-;7G9p@zYdaw*i=g1H=iuezqYL02leBg3&{g=1!)bVnhoWu4Zbj$=5N3cVl_&iEise*U$kV4> z0~JHA%)@Rv^Ai^%9@u~n&C`tj_DH_8Z#)m_CtieU$wW;EnH7F^Ud27kHwBQJ zZ;~unzF0>P{0nVXZf{ zndC|5zO`3anaA)JdUjP!XJ>H;)gPUmoqcLa5iAn)gD^s?PIQbF>>PFucuPBbdX|!~ z0gc3L0&rlD^kz?c+f+rc@_Qk}_NS(%+R*Kf!rT|2dfnJMP{&}&Xj0Gj0R?0bS0U$7 z=Z46o{!?!VGP1#jVO{8n71(q6)_yAs=L{pmJrb#-HHqiVQAt52``j;_P8stX6E@k` z?Q`Bjk%1b_?Y!Vw7I<2s`JQFLoceGxPS+zk3k|e8vmV58y57&s*ci98wMrvVvk6hI zk#^|~|B_er6iCA(7y%pUS|BKUmg$mIrMm3bj1qSFt_|EJz(~C-f4NrvSicC|PaI-k zaR-rm^@!M6J#V35eM*S@;P-v0KQ12xf&XIll?EM7uJ7ghoTpgXw<==ORiSU^x;#c+ z6q#9K^^n6v3!nCWN4H;j=CKa-cx-V&k9U3bKwi-HM?IuGHaNF8sAY+16dFZlSF;tV zd-kDw-}Y>$mx&tx>*-Br46EWm7I$4Y<9eN@P)N~51?)h?5q|8Xl#ha>;&uuXb+&@C zj|XgWf-+vr$w4RbD$^nY+JLsM*DCJ*A{)S`;>t^ZR~~1yuNWzP!u;FPJTSKjk9hdU z-&*3(=i@X4|9I9%J^r4R3p~hSM}U0&YlBhmh_6<=21ATmBwqLal-qE7tM2`JYiG1q zczr9Wxyaf&Ycojp>*&xe*aEUV4R2@4wH%6m~kC#uFjC8cybYz|8d3#`- zBi)c?>a$x=6DPc!7_Q|MK-8Jc=(~XqJ4pQTgL3>*M5`T0+ILWCd?hKX$z^muqmWheYhA)Yx0bc8krB*0y(f^JF;EDDm&DSz#Sq^`sIHL_jOub`NZa2v~rDpYd?H6xm+5jTN`HkO)$h^6%CHu zZVX-DkCF&sMJQB@tBe@Up%Gmmy@7EO3rZ>s{%EW~DU6Y%g+%rFl}a99q-V!GJ~*YE ze%$ljtNL5vC!sxcp@wTERlnzyZoVlG(w`|&53@7KTj9{DpEVhB3jCWGI%gIZq@BG1 z>&?yhxzZU3o_|D#_jy#Yv5*)SdyStH18ufXR)$u+X7YAnCx^Kh1MhB-xj%hzx2DU{ zIbsCSv=!@o%Mu4V&cQ()RarGwdj+rXn*Jduxau$Xo%MRZ6kX3K!EQ(^Iox?fAY8z- z4?|t8pr<YQEi@C@nL(8O()RePQ6B8`G zPVIJD1xI;umPQ+YSv%&ExK;mmEWpDCTY?5=C+v%)xQ-b{y3Hjcu!AhDjtLbERW zzF=1WQY~bZ9z3|JDBhVff9e>=!-wap_v1u_>vC@wpf5I{k38Hr+BgHl^(gU-O>PaH zoHmA)LHUYQRIGd2>ZCq4zLbCL<5i!}PG5Ae1M#u4!V1q;M zK3QtC_>tK}jsAuYYm#Y`aLoNE*>OVSOsV{d0nXmNeaJlw>TWGiXjI`)sQKfQ0z{<0 z5mg?w#l}12?Jy#e>Qxpy#2Fd|cDJd-P}A(sdtXrZ3% zTF6bP6S~`u2S2X@RaMLICDVyIM+ukdw|fTf;|Wand%4XN=Fu1hPWC=jLXW^ z(_nsC35R=Yd)%cIuwDIoHd$8}vP$-@ChV=zH+6RZD}w3c%Om6he~u@0Ioa8C()ZBe zTEMq_`ErYPI0H4TYV%e`GYG2^k3J?|AL#1F>!P@aF9#g(n#`(?5qV6^NOl|-j1@|o{)8-A*^@O_Dy)+{LHKU@6C<9Q4+;Iueh_?qb*k7E>|F{d%am+ zRW9poa~{6J5@AuoZT?2vDVi&RC>r!M-4&x>Xj_na*Z(KPoG7cNy`;DR%fP@a*hF!bBDy?3$PMEci?j4w48vf$@L zG{^;Qo7s!@Q5vM4>F!%?B!7&h7p(NHc^PW`k`$f}^v8~e_sXhQS?Ie{DpBy!(P6B) za&RyLpTA*6Ht_HfMHAU5YwHI=+W^?IQIaVJ;cB#p0br&VS?*@ z=F;~xz{YU_tDTx=p_-y<^tsArPE^IxMNLC%`>twInzkO!e6yv1T_o63_{g0F=P|8- z`65${zMhB=zFS^gYnzO~%++)$YhH%Sc0?C#+x(gQZFCc-!&dWUd!?uYyeMW+3?*R3uTVOAdvW#nq&m)fjILJ}dL^?_#2ef4<;O z{S8DHBx)nvQm8*a&^sEguoPaqh1MZ%f6AN-u1rX&0`U#xq!L2`W%2|HJ|{54FGTKp zFy8%I+_WGb(5RNASBUzc@IqsOn^L|WGjo%Hu4!1eri9Y>ar8ll4|lC~&D)X8n=_9k z7}*o&j8w#(f;Z0=@(A7V?VzF$)E$Kd`V{)>&*5uU{R&@)mg`q-`xQDs2|d%wko16s zLDxz7ZOM6ow9Uzw@#$yDlisjdghG5yA|a{r7nEDK$9!;KISMX*pk)WUz!Bt7%=OPX zAgDY%Gv5F`poRv{G(EawPh|JP&d$`Yz5*uk3Ea!wR{aC&>G zr$B_Wr;-wY63thT{hp}xoBwU53@J}eRUJ05CGBBlilbdo1)G53^yjqk&!M)Ne+K`q z(H}37dwP#a3`wwcU{wRtOi6V~$qPOVfk+!iu8FBc`6)ng?lPTdUw!-8{;rJ@WwuW~ z583?!u5MEtO8pyijNk}`-_p7!N%`jH zNXHIPF_vSx7}%RAawOZ$4vo!WoRr3k)%Ig1kM^qjYWP->4**f7X}v0R*?VSYv}&t5 z73Jv`&0{r(Pq#aT@CZKtfzI>wdd8FRMMS@lMQy;z^6E&aeXzY@RQRINDG^jf%9+zi zFQe(d8J#lX+avLM`mgMQ5Mzb+Y?_uyDJd=JD0YwWk58&Vz|OP$q4;(>NJ#x+WBqs+ zvAMS33e)iA(lyv*e7TBuaZp}I{el~DPOcyny`Y81SHX@YRT!XK*qA1y%yni5XWfP# zJP_u@lGjPtN!i-FHihq66(%h!j9rT9z<=%O}0s zy(aBoMruVvIGuaR)Pe6rg|zQ15{6bkt0G?k zQ$~?Lcs_6ZnfKCuRep^i`J|+5Yx^kl!WbT&G)1lA%MiX1+r>%edEMv-{E2i1ARF%O zuhf6j6Nu+ArLJmeB=17vt6`A(4^^8`)oBlQ7RFQ}m{<^Smp9(SS3LdNieATWt~n?7 zO`3q@s?*NJk7+D^d^vl(UaHd6|Lbj^ zbd|v0NOsg39Q4+9YtW>p_JJS@YFPf*ezh>WIrxz4Ks>)HT$SSJm99e8Tl^Y5)M^%u zo)b1L1ze9sFGMM~h%dO4F>!Ex^=#O%4AysXY&J z3qI2gfL&Pczp6(k8ChToy7V7v62O_W}O3P0tu6ueI#^z(LA zB{pz5dc5P|@sNoC^0hgKU7QvPfFHxy7(X&UlkHIZ=`JHvyMuXN%KVh* zbTJQ)9Nf3m2-~l2GPS-d>ALU%6r4nwRUgO`wVy-_Q_@~Gum8;(2qfe-NW>YsI8q;O z7Ce8n)?1`}Y2~$lSd<3EWR|iVXC$cHIk_c_(=99+4cz@oQ&wKSnkv=)E+Mae2L8JC z&%LyK&ZDP3Ft~gQK7J8S%Ay71iUE1A0{}daq%L%qP7tuB(G)xI4o$i6&%H$I9T4-a znbO^@;VS*l_-a6L+kFVR`hR&T?S3)7aZ2`B05&i%|YE(aM*KnG&Cu_2ArEWnD%w%R}4r2{x?H09yX5Ox34ORLoW#POd- zndX6i?s(p9yXOCJrqtCP(U$31{vmC_j4u6$w$^F#rs>EBcQ2pXtvJN+A70yi2>Gv? zC4UA?f8%mKEkQ}r<|X3rE=*gUGRR!a*gbDs=rP$`8@zOWp5*wkoYn@?-f zxnEm6UM+1Gi>&S_n2+>MFc}gt7`BR^AfI1AXDQG$CZ?}lc@VCjVGRE*E?Hl`6E6Bm5ISo8e?k=G`%SG&ncw9xRv=rtlhcQbeh+?9&f}Yy?9dO>Qq3-BFC(tM= zPA89xX|Z)7S3jQ#+O`#`+N<)I+XO#AXJV8BBk2`4#O%`V7s-`f4V zrbhpF;@_|X^$WJ~Y2TB;tO&O4N|2BsJgC25dBd9t^%rah^>fV?pnN(@C)k$Kj$O@k zpa=%q30GG-o&C033uFaYbAb+k0_>Cg`g09b2=KoOk1!ux0w@h3Z)3!i%*Hlsv|>fd zEyifDjd*SVP~DB|Lnsx{+q}Dhe}4&q@YqsaXI%ov!GoNCd=Mk5^u#ah{yV8|?;;xO zt@Awa_2gB!St_R4Rz!O3+Q1go~!+U;`56Jgmy`3j)p z4J*6PLL30=Yvkd!6%8w~MpZumfq>6n;vIea+S`gDYYEJQvcBEwAk#q2Ha_+fQK2s1 zN5iyy+W0(g4@?SEz8~Pg{wSW*5qT6a(gcma6yIW4Of!@+WPw$9@FHBNV05XeXWjS5 zN8m^WKzyqEw(1@APFM^?BJ4i-b_hVn$P7;J-hot?9K)OgrrNh>3&K%Gq@*=?N{+SE z?hBgERE*?~;hHGLd3$FMS^K93ft7w|(Gd9g#;aUI!;-DO9}Fc_os&Jvior5PgI3oU#9TACR& z!a@bxxEP=E2Q9jGh87h^I%a$dArOo2L(nuTWEdDY^iZb}>BB!UxI{_miG)AT>%pVi;(1;PvPUmLC8&)xvr4*&IULnzL;*d5mlBgs_X=92HO mK+XL~Ga4av4}Y@mav6$wAqI}tnflajXkF0zJ^!3l*na>?(iF`HU6fHP4AB@3lHF)E_fY- z_V)IUmO8^5-H%OANa6CXuC_~#H-CnG^_k#@i`&@PICy&Udtkz; zFyV*4i0_-7pI=*B`}q_fKY!olrTcudchY|IwGFHzK3?9Q&Q5XD3eD!*vzcK>I6u#w zieUsm5dZo3T}w_O{^tz%Glr7%`>7wFAZBcR z2GoDMY#@x1#W@qBw?%njyHoe7zw+SbA7Nw)$d3;iz!8!LM^Uat_ir-s6u$FD=3arK!>7&xhhrhLLJm!8N=KWnfr;wU1j_bFESK*~7gj?qju3}vp z-c&cV-cT8>ZjwGoayeD$l%s{C9N!9Oh?${xH>Vz4%cAvV9CN zdwCKLqKhf|T_Mx3Cf^gSQPt>W4BOvZu6{n`HC>g%^{2dqk(2!Dg^9U}>!yF#NrU_p z;+QU7!k-F9r?G-BP?KUlUT5J>v3iT~8(XaJN>TEr$EpB5ZIr_)Olm9*d*Q)k} z`$0_Nm6md}KxFtIG%Nw3W~I`&Yq$-le*L3G2G*js83cm-ZoXP=U|ng_)X6%ic%&Bo z@dQ8c#9K(rcZtZ~Xv0-U11x=KXtD%J9SJc1(H8_jV2qh0$Wr|Y&u^M;Wrkg^m18G4 z(D_r-Jb`$?s{ryzOFqKc+pHoB*phi{AX7QVf;i}_-ss0y$!%WG>?&I1&R*0DmyAwDA;Tx(R z;rsKeeW^PxyFQjCa>0Mb1v_5g0ru#LFWDa#r|8o@{BDEb;AVyYXD!+Tx`y+!KDszu z*3r>f>89`{6?_O+FfcH{p49K)%;7aO0TIq=)B`06YP4oG=en&(^z&dX9x%D`~gK8T?3xu9gxYy6hPV=E#5z^@=MFi^nbsw{7si~=}t0RK>4FLBr)@y7R)~@$kC}5Z5Hi~%e`B1# zCGl@`_YWlgpGSB95P}{575hKZ_*d+IOX6Q2?jK0}|ILTfHWx};Zwo}q1phMv*bxT^ zM76E?Ls}Cob^6ce3`lZJ5$~fV z{2BG80TG0PX2Qv=&-8 ze}uDlKsejsB|TP2Yx7%-=XVS67ji+RIGR}ddzQx~4ah=VbNrvnNwDO^>;LU!4oGKM za1(JA|H&y2kV1M#pOM35|3|ih+z^Mgjz05$FXIE3^CkXI*OWk-Vf20C1dw!174p{d z{ynjC03-%lsU=>6W)7_W5$RpWd`f7y^TK(PFBUiaQxrc$DLVuy`>0xF>?*~hXYNtS zQ;^-PL+oo>myvF%w5;>$Iw@Nl0y=AlQ2`$FMD8Zga*jFnOqjKMBtg%osvlY}!lR!@ zV|U^`h1=5zBO_eAJM18Q8fM~`zzcrl){?p|!14Jq#jzRuh!BpWW$;ounp!G4mOKy? zUCvAqAbzP32%P`h0Oo+C|Vdmm54s8Re^Gx;eS~g@mk;Uk#bb~OC(*T zUowK!(9G=lp2Pp?<6&MN@>w&@9s?xq4OkZbtci<%rZ=Qrit0@-V=$qGwA8rI#erc5 z=zmyK`V<%27U4=zc{1_zIu+#6|X{F4U=a9 z=hml!ORB}`iB)8}&$k^yX@a&hgdgstYopvDp^K+r_64~y|Ev{O(tgpoQS195<+_=( zD2g@Hna$7Jj$F|}>b@Vxm10eTlcYc5hF?CmkY=0xQxuoEUi4Pe6fk2Oo9F!3gJV`_!c$n? zzOfZbgv5Rwj_6+Bok+zH>~`wvN+{x?B5t=oY70MB4&nK*izsDnZEw>vGe_ zEKwyzgl(JtJ?_lUR=SE9+qOx!9*S~^X%_l;stUrOT}62{c~{?68N=luyCI$J7qO=! zx-~5%#CqT7g*e!fZZS_>nirHFt$WZmfF@v0*eay>5Nl)ykThJ?hOT*|mL9)KX}l z0d$)ul%(h2c7T*#`(Rv{FZw=Mc;vCnB>4{-%_;MX0$2H$AVy~~WsK?~y8~wD3B}f` zkf1oC388rJ!JMw1E;Wc>Tue}4#z&$G6vy+%iq0g9pPHEIn06!e>*vH0x)Fnkkcsn`G_HLM= zoSy1u)z(ICZBbEUcks^DKxyfpxjtzJ!Lh*kqI;o<$^Ff1mWFCka5fLv)>AQsxzvG4 zC0o-qhs&h=E~_nUT)|srZ6?)*qM}ZCjxDax@W!jV< z{1d&9iAna^Z|F0&vY8#-IuV)Y>^i)Bp?FlRbB8B-{xXu!7)`Vo)gddb{s`#k=m#5_ zkzKkGKQ)S`1Vu^`dUzwmitS1{a)T?Lm!H2WMjf+i9FI3SJ2`C6*eV|Ys>9?XvWb4? zLU16C{_^iR=?<|%crh(-`}rjTj=7}%|&&h>JSIqi|+!{T;^FimiAA2?D0#4*MrpL7> zsi6Zrrn*XMZ;x(H_599^H5vc5p}n5LBvx0rcK1_9=m#%ZiH!wE1Y!#nM%_Mcb^wf< z7mxlR@|cy!chaif>Bhw~VOe=wEA>u6d&e4Xiv+xdl-$ zjP)bCG{S#f1b#DO7Q7>c9#Z@JA_@4V)6&BS<6G3bT(`Vo*Nht9&1nZ^XJ>29L9#TZ zgOgL?d@%Fg*O2~?1(!cflnX+|!Vdq~G4{*A;YB zR6%qd6hc>-m`e#XS}Mx}7&fwcG+W87JrP?vS~D3XeePujfsAy03w!9AHdmi+q&CBCFDV&pR4Y2I)MpqEhegG3y;_@p)WU!=yo z#f~8F(G|q;zGbYNyZiRWsXJPRipuW9ZdP?AZsGfg%MuFrj})n1l4GVZPW$_h4R)i$ znUdz#)?BmHt4U$H$*J(Eq}prU_uzkwCXCTb!yfFZCLVyJ3OBZ$Cayh(^2~AvweDy_ zqI4?*zY%d7>iYWU*PG|-rL~%QpLL%;XJe1{g~sqozkjbV!4qB=5r}ZmRW^&qi4-=> zD?kw#Xt#4Zi_1Cuqic5G*z9?taZk1vI)aqe;|#Q)?D5y3ayh%~<&+&7mjx#(B_;~J z_P!;kAhweJQDqqqz0j5p_@@?tmOgEcxB7;ba^WWuTUL8ui_);aCcUVYQHu zWKAdWl+CLj#26YjJc_4m{bOGdfMKDW3Qg>rLOp(W`UfU;#z5T{7rP$!xublISZ7C z2|EMStJ#1d!Y2mS*9UcuJ4ZhMn1xtduLiA4n|`gSTKYW(hsTk500dXXn+ci|yFojleXs z_}*WQrV43p;pa~;qr9H^@S22EIO$L=6@=cM@GT7PSuag^rcU_ZhbF>?8k)$*?>Y)BbeWlTw#e}jIXPI0`uCm5PF65? z5bui$0bMQk-`b01Iwfh(st?ZcK`1IoyY*NfXuqV@P{y+4dD{Zf(XJ69z1G3CSTx+_ zn<}-p*`|#ScK=S)w^-NgKs1onXTys_J)^xzMwEWP?n@jJQeFd8Qpf4&?ka; z_al4US@g5KV!u@)r{g?GNL*n~UCCb84DF+=Pdcs();w(+y2_!s)6+KSVz(>JYTR7O zhCeotS@d`7TxQ==0-@4c!@S;0ccUw|P!2TJQ~1G1rb)zXrAbCcXq&F_gM82Q4ETwO zm^b*5t})Wi(d@`HumO`Nc$RLu`d$0i7=4jqfKv_j4-XPO&Z)161FEbw(H zu|~D|aI+XZX9X;9!CE{)Lkg=wCHwVz+g=WI0>10V2Q0PK;mY!jCP0@U^BE=uZ4y_! z;b|9+A`K$o&rG@VR!<}c{n+ELYfPmDHf#1VQs@M0Y+#0%$6xC{4dJB^y~TFporG8K zimYovua}k}A|>rV)qeBQ%5N=%bpI{t`d}!80<9rs--sP7$SM4MgbWr>Um)z&;3$UQ6@1& zVTgJ+xf1}geMk-imA@tcDy77&Z79|HbI7+tB=J@w{LzWoPxGPs=WyW;x{8>y2rKF? zpx$N_-DJS=OyqIdL5)$yk0#?!H`Sa~eZBvQtkep#dv2j`D4SM7=s-xLob%dwb)gjW`J81EIH8|_Bv{jzMAqJJo5?A>OS_xWengb zXd-6$9q7$`g%swqj#XP|RM7^d6%>em_Np{{fv$>ZO=hh77$p-S7!@fBjQjZHf ztav$pho{VGfZJsnUbocPwn> zo)qHuN9y!^?*3oZn=y0cyL3}v)ZFueuKm0H&5p669r7wFVmd;xD!_x}($Yt)Z>jTH zNtuH0NN@a0Es=XAD_Z7WXr7+XPRl#9pPXmo!2ieprdOIoO1?|;MbiyDs2glM9_)m5 zeyp!gadY7=5kX3f_VV`KFR}3|w#U4BVkew#JbKHfMn!MAgv>KO>FZws7M5k#B=5O1 zU7g=?u`1weO3r}xAYkdvsS^?Pj}CP~l?Y!9QEx{n5k7C7MyuM>xinz0A{rPp7>#Fe z@6JCTb+z$}*YgNVZ*Hz-{3U6vmtJTfrDhUx|F*ZYsxM?=Om5OGW>Rp$1f%jRYV9pM ztn7#}?z<(li(U&;sWo5j`tU-#`u%GoLmze>)$>Q5KG!1B1kUST`XGWq`%^C*>RSUD z24wvLbln7{`2A9`Up~Cj3gC4D$~6K)i!3)?3cD-U7Lnl%BW&MmUbmeFdv(}U&-a^q z>3J@-_@F&h66?KpN+<}AIy)B-ySl!2+{A>M1l7i~O2dwIdgi^sOCQrrpZ!UC=6-Jw zKzZ1%IV=l^ukO9`vB`BF`f5B((}T^JzqL+(pA9c}zbo82OcCTans%#RyZ&l6PAa;R z6|fh+hmz>R*FcTog^$Gjne8GOR+nx9@F1tFI7)3X^B%)U{F~OhaXZfk;{qR|&G)?> ztlSxwb(00OQ&m1jkn*`C%e|B7SwcV0^7}mWE0ifQQU5V^cOYe$w2pY|QEFIJSa4ZS%@PcINZkUSq0fK(!%MLc{H zBC#mBF8Y$X*F)yrB4`^LN%48kqXTE_1N)+i5+c$>o3F>rcVoJGPmD%8@;mU?2f0g# zvsL&)&HPPe`EX;_&aLTog1vUi44-3dN;j+P4?oT{$3d?trKyZ5OM3!rGBXcGg4XL_ zK4_@~3yhrz>wka@kiKD=;#6c9ET|w}9sr zZrC;X7q=NxY~Q@vA2PlIL%F`ScUd_E1w&L zCe?3rg#BWr`J@X-Zp;N9NN6Jq+|F&+6|*P@QbDV%x{n^)yqmUT4`QMvCiYh^@l2Ib zCJR;z`ZxrRkWe@7JwU!GCGuGvPU!xG8+_1v@MeP+SF$??`s6|cXZDbXBa(?3wWNjr zQ^x{nkGFMq&Y-Hy+Jmo#U{JS)!~1XOjnI(9Bv` zT`ndNnBf)ageLv7WW2p;%eiXO&#kQ#rkmj&qh3u9WrU8(pmY2^ccUv6oSoZZA~|lB z&~%!2Ghb>EQ+>JjdV#cvGG^7PT>;ge^jiFuc&Rgy6J~4AS#4p0=B-k#tM1F~ z^Du!DS9^M^Jk&|gkVPx?8)sRtiOB}JT^)~X^@qZ>UZp7w=iSMeabf$}I3c$aPR<-f zTThbAK>?AYW~AqL#S7Gjt0irlF^(m!r$!f&+F&$_1>2tDD{n>1mK6i>)77!Vz{^_><}sT-V|&$>9p%Ra;xVA zjd8^4*`-&$MC8ld8**xzhn@uD52p25Gi?%**RlP@6-Tiu(zGcZ(TcX-u7n(&c^H~# zN;N(wRrXD8>nTM8;KQmhcYst?C8elCD(d^ajPs;=sY>G7+t@E=Iv*weV`VQ5HQj;I z+H|@-=^S-s@&O0TAvU=6hUH=~ElFX=+pm+_;G(LAhNL|Tfd~A|9f7teJQ74U1;u_y zJZ;n22dg|^(mCqA_4T`Rwi3FnwI6NAx8s1jX-B&h_K%M2Chilg^8IUU(VmnRf;T-5=u2na0?`oplvwtx7_F7O3dfpLEAbS4sxphIvLNnd%A-_e(Hemk` zHWD^EK#UBF2t2tw+;}$iBLwi8Bn4t$OlXavIZ&hpu|wN?$9H!J@*HS9{SxO2$Q;@A zcCU-UtU<96{iXYz+0fIvW(xtcCz1qNAp<7?aN#nB*GC5x`0B-v&ywVZG8}debv04+ zc~h_Jb4I+ln!0N;sBg${CF66#rmsfPm{nq1K_3n$XQE7-9^dYV^q|X*9GWr=<_x3I z=%Z7MH3cgj8?fIgj9Q`7EMsv=jd1psSElS#E0=}Gs3VTr@9#P?-A{1W@%Tn>#B^rSh(IQjs1gsj-AO z%ZLqStXj;Df8R+@YF{}mNqgTiU*Boie(!V!L62Ea6-FZPY)7olD=t9Cp&BKMPkilO zN2o_06wa3X!D$k;)>ik*xP~cIQm%u8$u6HD@mVUOmnWH**WmZ%PjR7XHD`AR$1XWk zLE;(cyyLMQ{#AC`x*o=pFUYaDn;cM@y&2BA?%v*qFX|>i=d?|0^txYN_*_h&S2g=k zJK1|I7Av&ili!WZT0V5!SG!2L2F$9YORMAhqHyzL>sIrb@*&Da{|}ob$566#vA*~P zVRv8qsKfwQ&*W+?C_c5Bh8?tFStsX$D=Q=`eA zcZTbBIY~(qm635|dxSILjQe7bM@r~|{2TSGQ#xJKVtX{ZhATrV>*#9&PqFoECxH}+ zH!mhVLIBgXBG$CIMTV-Ih$_BdcSD)}<9VeA5M0j7z-98zb!ekNbH+@Vg<`J+7hV0M zNUgNB;2g&5U>h}M!Aa;`Qtn%UO$R+Tc?rubyP4SsN_+JjP0M8aUrI_MVQzABb90fc zesq?X%VO(;-rnAqP8*NO$lO^qMWVBit!Hba>g)N4Nl5Bmj%V#%WkbKm#Cv2i*+3>( zg43f|%Y+t+wTWqc#gLg-Ji+14G95u{P-?GZ6|Yl>F19EaN1d_r=fCck9s*t$^5WOw z55~T_pAlb%afz3<;0{E#w&BUNmx+9)zUq$|4h@-jfpQ8-Sv%CNczeUE(LgPbv%vQd z00=}<^LVTCAeAY-L6py!?okpsFNVHg)HN~PbPa=Sd5h=n&P2lyg72xt33z(G0b9tO zah9XcLs^$M1M?+dMfPVBeQNWY-_d}t@_dRz_tpo8E>k$^3{3kVcnAL0lN0=!2Ii_J zZWx*>>@M8bWgOFzWLDEHe29BWN)K{+WYKv9C!-q-M!!bL(39N`#W$XvC6;;cUD*~b zSJ$)lT!mFY(J$<8Qu8!p=l83&%Is4R%$=?4yXsHvCbgl`!d}<>L&?iwbv!JA*F3K* z^)Gxr6dEhnS2LlN3@e5ttTEtOy~|V{)yWC~DY{xDh9^4YF%3qtj>=l#i&&d<8Rh_+ z$!EJW-HVG)2L^usC*d!8$1>Ld@_*XmHl|D zH~=pW>S0Wv6GlH&o{p-fmcwJ?tNW61mkQjj>A$R?k4H-(?|wgWXoFqIAl4n6sowr| zB~MK36w0*z>q|Zw}U_q9RWfiDDAMaBP*Wy9qwTpPOn!bS` zw?Ff!rSZILh7OInSQoy5x<6Dn zl_A}2*=d-Td$1L0!-q1rMH=PdEspmcY%j>z?##y-X56-+9XeUUzx3jLu{qTQUw~hB zF~+*hZL_k}N&YO7owN!2lc;??LUW=-t&OHTGU_Qta9Wj4eLk^|#qr96+%VdZ6uzsD z1rB-6_RCb(VLlr&1jC-}Po{2Adbi2zFL&`!mOHRb2dI0dL+QC(WoY)}%2P4z#1xt% z5l>$YR1rzo4{ixbudkq(VVH&fhLEM!=v;3v-Zyh2Lm8hKH`Bd$@@4U?#b4{Irv=uj;#7ovcqvNWzb8RBiZ@pC)H!E z=Oi5o+cQRa=hh?!+vO)+LZwfn-!1mp21)5+qyVO2Z{hL49tLHtiZ8y&ArJZ17iyx_s7To$1`j<7cuFA>G`N z2$1icgNA7|DsB}3k))*~tlW0?u-oi|c?UOpIwIkxwHv9My~ae zEtX7TM~bT+H+k^B2wwW8@g)z!JkPh5sS=;_ywQv8MN9&rO92s@HkVTntFjolR>w>$ z5gJtzYByT)`mqhL<0KpJndvQTDo)c_CzPC(>-xekZVNY#MI^Ub$nDTwLMw4G{hS!M zQ7YQ$gIOSmJ|9y~-iUyXJ`&fXHXq0_Xg1#|*ocDG6W>G-T0}oHbfu-2Wi{J+w}^vsc{r#Y3_7E@kxKtLDc0^m*4gT-xHnx7$<8o^=Gxb}y2> z58rxLa@lG=qL?NZA_akWz8Z|Wk}O_h42L8GII&&88ORVO$>m?fN{jS)w$0DoPG^hJ zmi+?=gjhwmw){qCc-r~7vk9!EAAb21-?3)lc7gG7Jn9(RwkVVMlRVC2>3k-v<+I7) z$tZ~bMxZE0N_xcfJG&;scaH0}1(-5o;EOqz15tsLq*M#(ec5Z0!mdD&JXi35sQtzF z;e%=4rtJpyCU?P|Jd7HOMnd`SoC@6oU!m0bsW7r6z3|PVYmhGBzvl2%H={lZS;pYt zau!i0;37fFFDx{!EsNRyxN}vB!XqW&bN!Z<~=9YU2*6X3O z=+JU6Y}YTqu0zZ=f5~gS>Uw9@jp?Z&B2jfRgv-;b`4Mz1-$(ODau>S`0fRo|upq5~ zS_r2j7dhB?gd{@GY&7SNjHMrvDG-e3lYSWtQ?2t;3&!FZyVlN z3XQw8*!R0F-RiK7{H(?&_xHZ}%yN%K<9OcK`Jz0MBSK=s*E)TC96l|-rw}Nl--6gHvjy(&m0ZDVT-hbh3 zd_o?&X_35vFk@h1^78m>b>7aU99RHmy2&d#&Bq#=T)bu{tN+=)9vWEJCzEOV%P3PHl#0K5@D+c8$`^VXJgcinme#|w*~yo~wzDYva~{@$ zqwYT)%td)0^m{w@E5FeOo(|#ZPkOZ|K$Jl_c5*o>rty5sZdBe{u0#g$eP|N%X^72} z1zrr0yO7lBTmGUVWN2_+phoU=hYwxSlyAZE^w5Y{l7Sob?3tO^#&_&0W#b3giJW&x zKa_9+G;;Zuwx>@tj5S6MBR){VooX28@nSC6qRa5jH?zr_g;RZxJ-YZ&iu-P}UG_4s zjH4;-*lPp(!RF+3;F=qq$M=aJ5TG#!zCab2m7A6uL3G3&*U4#92$r9M&XH0rd(yrr zs}l&^3f2}QkbBA0_S?l!=MQDqbBVagZ(n^Gy&H!%yIP0Hw_xk@2>3-C1wd`rzUa{X$ITczGU=3kU0K&OQstlANU&M_J)9)4dIDyNdgzQ5T%utG!ss<6KoN7?vM zu8Cs$39ZBJ?l3Fc<+s%h%e%!h)-YGv2DKm_KIOI?7V5r7nbsK-4 z;?N_`yY~r%Hdiy52eOVQ{^>3ElIh0ZtN;iJT@&AYp}+DFKA(U5SZXq9yCZ2iO_12T z)f_++NLQ2hcuGaV?B3#H>(K6YG1#pgR0t`=?W%A1rxw7q{Nwo9YN-XA*Dc~0OE69L zp_47(vNlzGEYU`d666x2MH1nDOB=M)pad^!gQbD5~~4}d7xalIWL%JCOj70;s-C1{RV{GxVlMoC2> zTI!Y1POTZR2f--}Lg#CmCl;Ck{ZJs&FGcaewjuU85X8Md6VBbhx*r2{4hbOOP>W- z#9~FZx{|b$uy;^7LL4X3bD9blaT>ZCLUwc?W}63b>NTOa9NtEy{KiO2%Tu2o#2X#yc6?Sc6sleChR~A`Kq$LU3_5c^KpJkrIbEG4n*Ir z1zpI|+#l_yJRt-kc2SURWj4>*XsCm>4BtpG9x7v_T_e+r;1%uMWyn)+I;y>~xO~w< z^`FUV6k064xe81m>>$Vu=* z)n!%_M)Nf&8mk$}XJ23Wr&BFR> zMKZT+a2)xld^=yFtTQctYuhY+xP%hZNa7z&{G1*YY$QBSPJ1swWC8DXihWZ;wHchC zM3xj1eNZ>Klu+q&!QOa`w)tU>1Hb-q#C{_pJ@aAfLJRpPC$G1XFAEjM40FPSd|$v^ zN^H5xPIbnhk0Zm3Pj(A&=PR(UINU()O#NC|dVYhXDc3&bCfuj^(UaQUgL|sT5qJv4 z3T~&rik1BxdrIF#XeU zurP(>%UdFcLopT5|K^Rh2E|`TDma-OjvPq>s0dBm2X-_>EiHlCj^UfqxxR|o!I+zc zn+I4&y1jqp$S6pp|H|~kX0TLnaW)b8C0{I7hwVN7tfTEL9&AhH~`@yR+x9?H@Xi;#Wwk@-%&9%DZ?}m*3nO}yq%<#Qff9c4+#}U`yjb! zOu-HK*GjPiH6OipNKTqo<=ocA?A3wINox9M!DLp^xcQgFHtb`+o`(Hy(m`C>loyQW z(&^lfZ(YmJAPq|pSfx(pt_A;~j!^%%h6Qq0dKj^1O4zOsqEY*zs3fPFJb9|Bs;IGp zeXnH2{Vcz75<4M*R0N+pm7tf@j&#~@G5IMTw8j+HG4kySQk5Jl3WHz0HOfu zzg>2L@(nW@>{9-EV>!5)&_`2lThxOsCrT1C>{Ha{6KgWH!2ZyG_|2lP;_S#=@GHJv zO!b6bf?*wH1*bQq42Q(L_qvIvhX>S_wZq61xC>O~KJ%cVDK!Sqs(#JPLUh?nyuLyq z)Y19Wb}dg{aT^#7e!4f zh`n$Z=a`vkxAR)NYlaOF+yE-q?3fdj6k{EO>nBuxicq?v?$JgA`uV(hDKG>`2KGd8 zc*DC5Rh8EI)2JN_CwrRAnmO?d7p`PJq8_1K)jGmzo0QRl%ubXL22`gbUlSUuIqqCl z0;i4i=WRnv=n+jov07tPQvj_Z+sjuom-xNv3v$~Ty+u|W%gf{&p*#+rv!mf`C#zX1h8@RaeQu`oJ8yI|G{Vm!R}BPM`A2k9NT!`0rs9<6)WBMd0F?+ z!{g}bVywspWlXD>t!-oXos;bK?si~IxAFAljk=CvTkCF(vQxT$+uwPQN%WSL(9S4(a z$WzxU=wP?gGciF2n&%&<20xxR>k0fgqNDPuJ!!I|fx9DY`5-W7$Hw=EL+veGqy3ZS zb2FD3CYT{%fvFAelKj7Rgx0KX%lp!Z9M$>550$RI6|f+kPy|voCO_c&_!KOFhs7F6Ex{JAXn?O zNvF?DMwV{n6g#oEw>in^#1;M}19!j`34CiQJzQ6aif!*U& zPv$*~SS3ApOM;FJfDaSKl}};s%te(mGfyI^>q@gM1YQcVy>&kKCxIWIL`;1el&X}H zaOFX7YmkdCrPppCdKvJi|L=<7Uw=pY+MN; zNf9dQ96BnoyX8Pa3}#TW+DmN&UzB_R>|n7jS{36G1in`~J&Uko$qM;rosXauOH?H;=sN)|~ogyi%_pi9y~5CKbj=S#X% zT{xr93htLmZV-a#|J1VeZf!lEsf{WRC!n{i6zg@W-->rQJsU6OM4Iy`C@+#M4 z_K2#Dj~hPt6!E^)+@2<|P;FF;4@wBZlFV*bm|U25wtmB4JN_bopS$Bq`eOESCphV; zEW7@H&0+6{7334TQ8ez=z-Cyn+epI|$~_aDom&ReWCA}l*R^o^@#mx6Rr+WyIh&g>Y7a;&TZ zXY}XMyK+-q!58{~fs1zqic?BMbIP9)OVbK>UFN+t_`I~8x?NetDQ0Qug7)s!;j8GS zbl&EDN615n&I1FGCcQIFCpspkBCdGprons4pyPG1$;jZ9_RGgX3iAw%A?4D~<=~rO zi!R&d4!R7c?n6xZ#`LZFrz#9DRdq3Ds^{FUUmK_Aa`hM%@K5tj3=z^gt&8PV8^ZzF z=>2K*78eq)Rm8^F&X$$|u2%~twdZnyur)35#ZxXR!U8h0k~~6Tse!?ptWPQAyF zQME~{QO^ndsoA8>E0FfRG4TEDb@B=6IXy$JnOg+T@^ZPo@@F$HNgD5tVAt=O3e#zA z_G#8Z5fMB1xc+sUz|*M5r^yYLXNVxf9O=Zt+nau4lTrw-{!8XNLW%> zS{ocJNqxfnZW!Vv!%>N+_f3*$s`km&)|WCiC+{fSrq9Qf(Unh~okL8xA!uT{y7jSb z#oAE+nvPH(A*=nxaJ!Z9gO=AiBDpHHC|wN_Zy9IDM$iX^Fg!6^1%GCtIx|abUm!Ze z>$wRzIZan!?KRUOrhJ-=Xz4y(!2$9;z;=FSu2}7+x(!B43`qm~f{i32C#ioZIqMW` zS?uQk-gH}iJqyb}M#s`<+hW=VuuyB)h>Dv4)ql2qY8uI1U)Shk&oHCjM3|O+LAIKQ z4`0VWpx-3R$Qz2_k&(U*p_d+Ddu+GHsne7=7vNAt9kcxKrQ;)rDYT=$?z0K9QUCOK z?CH5<{_#t)1X7My#$ulvD;1Khzg=opWm`4WTi~o}pDF98lDN{>joOhCV|M5S{B)~m zU3CcyNH%;fvk$~oRo&#>x2qpJXsHs|4gnKoYa`TiB4nl<*sq*^AS1Io4NMRUZ*R)Q zllEiicG(x@OI_EB+jXIDiRJ9g$15?*=j&R4i|d~R$bv&M-Sv5eA7G{guCVN`9{`Tx zFZb5{EAV1gav0<6+dO*H8P`|luoB4aPrC}$tr0}+_AFYQxvDarA#dKV=s*2p^(8(E zjo^91IT>{yEpN4T%`5lIpJz;#NSI-8MT*Um^4Dwjj9d2kSPZ zHzsqfYv&2gd@Cc+`-^sEj14X_*}qBfAmVATPM6>uwTsuhJTMXcq}dc zuw>^4(z!64@af)A+vdvQtgC(f2ojLzucx~!L^zNjx$y~U;h33OJh8u+qU)IaTMTV5 zG4!g{=3hW~6pyNT#LPDFpNA!WJxk%35QrPuqr}ccV?`W}X|t#B zBzuHZp{;-@&4J?6XpjErQMtB4{SvwesW2wOt>%K&ZkNZE8YJUvpCYrQgk^hX@EcIf zmj?dZNi$J?wg(R+S;og7$_tR=`xP(%CCdDP=gla4%{+)-QZEfTALOdD1ov5mCQaA` zM0&sUvIYYF*b=3=WK4>Hum`yvp^H7;jwE(lB;@-eD%uZh^Fwo!*k?@tYf0V1U{+xX zTq>nBU_v#ka@fmOApMD5hu!(jhK@3hx~E58!VBEvD@#@Zfn0C-*tdeRI0?i#clFo$ zJ#J}^E<0R=#L}K_FROQMwDK1Fs7uj;Q5EK-U*1W$A@D5xf-P)X;gv&}>(e}<_u};f zX7>HA=Sg8(vDxjQ{U7lB7SKb9mub*-&2{20`|Puxxxfoz9cslzELxN z%KMMK&e4I|7MqeleznjU4iuiMnzqQaK-U}e#$(D~FJ#zjD?L)@u#`0fhC|Jc$-~9{ z>Rk1WtWWPiVM+J6)Tof}NJX$))N>nvrOV)eFbz#OprfQcwJEmc^a1zn5?$WK z0FV3SYP@5`;Cwnz^t1V_sOX!Q=WP?~7z&o40pMo?YZTJECFWNn?ZabZuf@a=dfu`Z z&NNN`=qc+6B^t2*Pc#QaZl7Sab!Tad*9(Cu4bZe($BWj%_JaD^-E%AO#)OI*;&nx7 zS|M3!CGK7mV_!?#hL^Ln`7v;I-pJz$&53y6wt{}s=9upI zHIXL4x&#PYZy%jh215Y5g!lRG&WD-Q>q+x5(^Lb`IW))0+%|BuJO5?_>BmKNO}Fj` zfIt>H;PT+sSp_F8A#>r4BEGFz{+Y%4NxE|J!^7l(`x@cpsW`QZPW^y6Psf@TfM^pQ z;H@ntk|2>oZUY4>wh5j?>xM zS)sQe_tR(sv^jl?=pSI)t5Zt#q5;nG%6Z3Wnulwxz>$U5Y1Xz5)pq@$vgf*xp7$Q` zYAle2umLh@WBZE)so^!LL{2U)N3t?FHz(K7!~Jg9JB%Z>;++RjvI8E;CCFRTPL!z@ zVwZ__eS%j_+2RLbf~=hI_uB_!%kQx5W;7%Zq7>aOjW|zr^*ewPNJ+ArcJhnU{p=dO z8;Mg_>K6= zc~DE=u}9xKF*`$FGAoGxVAH304>2jXQwJN%Bv})BFDr2EO+pg1LK3V8HbcbJ3sPrU zZEg;ee%D1Yb6W@nc4ZPc19&=&Ps!ia&L0_F1kXXMpad?Ve0#b)#~wXTE`~47#1!&b zM|CY1mp!{|?@wQ-o)V!$oR3Ba`a?@bjdFtk!MvU8CTM*KCMSiE|#kcDH2v~-)MC;$u0R0>&JHX5A z^@Y&Q|srDEAihvW8t*(!tafmu=X-(~J85vGo>E zQEuP+xJXH>bc-O}F*GQsNOw0#4- z_x{#@tyzk*8Y zz!SuNR^uC`7nriX_M2PV)L9KQa;Y>^F5#}TPi0V^p zXUg_#;k{Jvg*}*09^o@CjxcF&!y@rDt`mWZDZV@H4`k~*`ZbW>rq8+-wHYeoRa|mB zcQ&{P3tm(@YfD^amcf4@L=wouQtPLH-leH1%0SsE%-L8*gu*w5FRQFAE>aVoh{t|@ zp7%Hlh;)SFXh?OkPUTus^QyB5 z-08-p$7j5hm94U!7fn|@bj3JU$p*Ht2 z?WyRg6SNZ$KQhc+FHUFGdQ}}Wy<0PL5E9QRgB1LioQi@V{$^LF5D&904-J5=U6z?( zD4LBJHHX_cr!4rCS)RP4B{8VSkn*6{ihrL~+Xj~xe}0U{lN4PEp0O8E!*IL?3`VSe zRfc`O#^J?1++Bmu?Z%(5Vi_>hT3O!*PV%(!HSqrQksHVVW~Djx$nWC*yf3Cy3!`6# zik{sg9J$AP%!0}IF;@C-?x6$q1EAHe-A8Oz%sQ`?Ug}`?pjGk^RWH}|#%Rye(l_b*vM=^(jGGt>Uq~QL? zkI*yU$5|g^O^VneQAa@F0V~L#l74&xgiIQ7&uBQ?o^AkTPUd5uJF>Qahl(*XAd0-v z*QaE@?B;vmU1#5)lS?st_6_K_wkPXIeFDdyNXdlN0#yh9%1k!`7acGc_#|N?XmvVoIMR1-f4!0}XL- zCAmF^=EbVR146Wc{;t<~<8~8si$sNt<(?L0X%1r*a3vPM3Wkj}<2f%v6B6Ff!ER%+uRt%6YW?*~8G(sc^kKck)1gc0uOSuw9(yOyPR>i+n5kyV2$#|4 zW&Q%5J)5>6Y*7|AH?CEivxcY3wohU)K(b z#^()HWh*=CKo7v5HcMApBK7GF$&H?!eSd1_jqTRav!)Z&V=U=dpVVIL6*2WDliu` zl@upTrXJi<%Z>*Ns%v7d#8-E>fE>a zA~7TI@(|coN=6MJoOX!Bcf`)y>2^`12u&lEO2_6H#np9^Gav?`5W6S*lmNztx2nbq zH`=-GU3?3q`oNj9QEHq_ENL z(dSanwk3Pw5x8XZ-lL?Yw2qEhZMCErcuaCiXsXBRky{!to|7 z+2TL*dW|7=eg zkAA6J9vi)}nLHiKt-~6wK%UmL9bB;xv;S@gZ~Q);A+WB!VY%mvydpT`=gSJqXR~U4 zj{FT=>?FaZlu4GpioA_*U=3B@QkCyDz)y_S6q%A6$LzP>m; zlb&_+@5IKSu50(;OJ`GK6zF(~_?+_SC{MEEqClb|L2PC-AE?C+xx$#_o(f@2A z!Nyo(<41>?fS26$7;)N5o5Y(%zeb|yR!mht!Iom>E=>f_;yvaviAi+j;^oE@nR`!~ zeBca5k#g0Chagztxb8Qg6}HWBXSTw{_nFox*4M6QA%A9 z5z2W3O+3s(_L0lZ;$~I6V&=#-D5EZ1x;(HY60>kk>BFmU*#(3K{Sux|+(^&sZQbC9 znsOI=BiF)->0~S-Aq>LUOS=S8riQ7(E63GyaLDD?lVa($#B_GvA?s8MU2!>qTC0D0 z0h-O1Iugj!oCHO&$z>NY1^F>HV!8xILUjN1KxsW7`{(4Eg>oUx>JYQIXSH*)50&^D z_|>ny>jkl?FPp{?t!?7YV*2x|Rlmokhp6p2?B2wpeJwZ`b3Km6Obg-I-He)Ic~Qd& zJ~m>P+xHUG$F~JdxPw>6ET2m{D`AojuQ_Wlq4wFXq6x| z6(LqKD~gX&em1jWbNbb7F1X%*@AFu+e;K{hZC-y;c7VO`)mGQDVk^;rX`(Dh>0vii zbr+Y}5NwOjZ<@kd)^f+?iSA6xHg)hO#*3hqYvKa(kV#<^9w%*uTMQbsNukcr@NH*~ zCtYjzaGiAB5Czp8ODS?q!TfN;V1zxyu2*OFDd9~A$20j&V(}o3ZxFcqi3<4QqI>zR zC2Z3q1X@I(f)!G`Sg@0gp_*AT=gW-OcJy;t=N2w6_Qj38 zn^Jdd3CeTRjT?gOYn?&o-*u*Es9FL71gHIK;*S^$7I?t)i+7u6m%9vuhr(>C6zSap z1d&aBN@W3U)c&@3J5GjPGjv8Nr|#C9zqmhQnhJN34mX!QL5fX}Qh-lsQ`pK_-QSQ5 zf7GhengD`H2L12%!^gY(&Rc=&VGMk}mzOu~zYv%EU)3-NgaNG|${TTNH!)zZ1s@QZ z6ko;Pd$)1cRYB8~Sw9i-P?uoI!v*_bgsxGCBq#%oEY z*q*No#-91^cq<`0|9Dg0YeeS3HV`V;pc;F`(1BkayY_@P$69JN$wQ_*99(S`seW*G zm$^|2rM5;vGO$sF4&*I!!-5_-!opsQ?Sj0Dwh_1ed{X8|cz=47vJIhWt?<XuijPfVAp#%`O# z1_II6`}zUvxjW5A}H3cx7J$4*j2{-GC2#tS_$b(JdWl*2r$3ME;2 z{0i%vguioLtg1{;QyA$tOW_Rl6~u^U1j59@_@<6o(+`YNd_1ZBZe8tkp;8$kuzTe< z=RoXS-;CM6XVT_UUQ?Ryl?_MFH&4`5lNxLXP2H~72NCEe)Z~%gOkOU#j2uRb3*Ws({OmWS zL^2w}Qye>b8_LR$e*vxX(mtg8fZq7Sw}G!mGee(CBo9`_|G3u{_DrqF2W*UxtQmV! zkU)__SdK3)L~j&zGifpY+c-j{fGoSS#;bPY24{K+N9bVrq?=|Yj@Rq1^MHw{JM(cr#!h{2_VZdK6_RVZ6pLzR8Z80f|k5U@d9%kg2 zRom2F&PaAxw=wFPSM?tSSdW}=>}GwBKSjSJ?)q_Mc3bF)t*d>zDcLa*#;6-?D#E!Y zomqZG>TvcJV=bhYtRF9l94f6e|73sht*ugLAHb)HC-9K^`;dQec&EBgXp%Yj^*Ijp z4^``BqNTta+;wA40ZGWC1`W}#kjv+Gy*Gsdi1T{(b{vGW1f3t4JW{DZB^)_6^T@d% zQWjdr@!_$ru?kyLVAvgWy$olthHf(V$+Uu) z@ZGFS1vQt85dV(eOKS2`Pm6J3ZmfFRvZ+XAb!7|o?(+x8sHvd2)5PpbtxYzifj8zP zH!)K|Q}wl9y%NaN$p&N`?D8&FLI(_uDT45H_l>|2V+F8&a)W`|N&X}a&O|ML3p`)#HhtEiRFhlMWa=hv0&(A4#ePV&W12ZLtb*X?Ov*`a@)e zApcVyOh|d1>-dB_;^^y!)ao~sFD`y)fpJOjXJPl&;Z8+ST|b^Bb3D(mwj=Vuq<(VA z^2qd~*ifrvJAEoy=C^2q4sgJx|3%aC?pP^wqWEC7izX?LLPl{nmS}yNh(V z3g`*LzLjn{4V7wU$dygA;3bV{B5ZFCWA=;l){dT;tR?am2`MduP|wiivuNG7mWaUN zW z+i|uW_WiP&Q5@@l3#_vn>QCFT1l#kmEowC}U@e$Fu8n;9joM*pXufp<B|6z|Xn|S6a-|(T|M|6%^xbyj-Slc?d+(jMC1LOO4?qHK$VMg7^azwajMEC?K4aJ}LY%7|f=-aQSD@=?0`0|_4GUo_A2Cm*peZq^tOUMKrUEP@RKOg5$ zYjidZHoYYq)Iyf5x7W~TE>e(CXy70V{0kBiROA{Mjz?u0?HWyq)xB&)Sn*l~NL~ln z6xCFXiFYO3&idQ1HqcVOYj?R{u7XjK6w4UVr@|5nx4B_r#s4{l#bYX>+ZuhQfd(@Sm8hn?>%0iRmW;c8p z%LM?M71BkA+p@Y)|}kxNLNkkf)u*;~{{Ka@)w7#$4Wj zPliAD0f!4w^c*q9$B7R9}ar6ZBmMC|ci4bpktLVt>@GNTu&cE+ie zEsFO4_=z^+4}>w)V-(C#Vdn48kBAq*^K0x4G!YY6UNtr+!*6~~K<(Wci7tk_);-i& zJ~K(a0swNjIdbP2@(5dZgJwpFx45{h^`c*ShO^}YeayHFe2I|DRY5iP+2Q;z0YSZB zY>Of#P>aCNdSojh4H!6wDK1D)cY6YAgq7(dw#5{i4;=jAr{>fo*yOWOv{I~Gyu-U~ zdhvFG4>i7oZ04;y{~IaLA}ICNoP>WIp-UG^KHQNsQatYbj?o7^9TKNW(-OV6WmdH)4>$_lNE%v z&0}I_DJw}%NcZ|T^5BqcZWe!J@16-y{k)(QZm@2@p=_*{@z_b_8%w~k2+U$+N!@=f zrOWAD=1v82YTHyE-xSofv0na_^}daNK$GAr>2gk3&JFxB{@5&_ln$uLN6Viz*y`iaz zm`r0>(+j5*p;q5C_rYB>I**SOa1{FwVA zmL?*>cr^M4}xzw^A_XXFg2*qwVtm7FKlxSk!YmhKn-5h=pdHLHZU+7 zm@Lwi5J^olpF4G#RQMJQiBwVPRK4aT`9*}lx-t|L>ZqeFtwFX%5)Osjox>f+pHLC_ z)Nl}h`C+I+1Iqd>J6Ufgrx8cQ(}}V$H8_yL>jvky^qs;g4)Og~5-PI+sbpsp_Q6(q zPcY#jdZjZNv(q`%;M(#|%9w!Ax9m1Teu4Y_l_fOk5k<$me1yF+$*&qGSDEPsdyN?m zdR}VKBk$CnNC!#Z{3`kdbk<@g-x4SNt+nzRuP-)oAlzFd8sTEiX4j!bn(rNqi3A0| z`q8BtIzu2f8`o#aia&m!Q422|L%E{9PLepgS1c>6cO(0SxtC&^Cr^4#@ z%IG&#Z(PqECXL_EI`H0jojZ^^EN}WCca~ToW%iY+n4jPbBL4OslO_&2N0)Ne6e<}; z8MV4UDO!kCVA-J0*-vy{TU*@S+LF~jDzBpSI{UVj`AdoqYhK6F)-mK7J9x^_0RHtR zO;Lrb%*AYptGn>=YL!bs&K(ktQR8%TPf!<;N@ml|X*iAu6sm@yoY!M3ZenveIcGf^cYxxsN4|0lVZ~xszUf zm5fYVUE+Bya8h!7McI=qg|eOH8x9w^Op*5;jT!SMwoiujf$$WBVd(knYy!mJv=x^; zkuUra7+qMEICXy{PD=k>RGN7&=)+p@{*ibc7dV$2!x{Ypms0$9{H`_X9(4Sr!wufo zq42{smnkF1g|94Pj{@idnuV`U=plFMB=LE!SblRH{c7bQpf|ymMq*v1(Z|)(cFy644^yEn@ie)cvlm(};_Rk^V@hB3OKyhcME z!aSXer-zd%M#+fdK-I2}uw^97j^6{>%@!`Q@4@aK^{vkO4O;cH46wEwo3KL!JPTUV z(an&>HUk{bj!&@ai{>?gijoKXfnxy$H=_F!28b3dO`e<&rLpZS41k?^s#&I1CZhWr z-&S~@egT@w%iG&5HwX#}S9dXsb{;vlCh6%WKM{A0D&41PH&JP-#rJ66atOXtDvv zi83skjXRk-h+B$Ml9cyn^@O-N=VIupAt)8r&XtW$8V z7160MK)*498TVlFlV77%65fX0F#Zoc!!E=Q&9&PRJj76;?Y=S2%1TH!2_n0}{h-6A z#X${h{&jrE`9{9x8IxTBRykIE!MxhL{?jjc)^ngS;{`;fYA2(x%DdE%9WynT2+~Ia z_etFM3J=Ho@OQS~jc_S#<5kbc_r2G3mrMw(4_kJ*M@&&YlkLSRUm}&4CrqAW($eK# z)P1O_h&O&o$oun?^+*np>sE1=39Hl)dUy7fJKP;{I6o88Io`O%CY3SVxpW?YEP!@A z^V+?2Twxrjx*x=o2wPkgNtad+_|uD4+5?1NKm#Q|)a}3T=_%6G8m`+N zoge`We6Ef*HBGU3e@76X@GG_y20_PEkDoDZ$TzCXA03m9&mLG{u4@2dcGx)xHESy` zZ|U{FAi*aHAuqbSK5%Z7B}yQB)}nH`m6}0NfbqsUAo{>79qyHT96X$f)28|bO}Akn z!87UC{EX0%7imzdulbR+i1$Mu#`NRI^09l6dXntDi}pxEmZy>@#{_GIbknfw-nGKX zMa3^XgZ%uiQ8%8^U9dcd!sFvTUZafnL|{UQy{51Dpc9q}H>50%Qg7)F{XG5>H{-@D ztkiAzFZ#BlP;Yq+kLH{!!J8Gl`rE5bXt636qAlxPuqtLq;n}qyO^eh?F?`;x?xWTB z)(c5)|4Tzse~OPIonGGypg*h1(K4siOkg(oN8e~nU+`D9i1V~{f2YO2oNL6Ckke%R9wBu^1^=k zvXejy?P$%fd`S|GamEEb!QP&|A>mQI2i}p85WdyR2GD1Y+j$mM3|+Z^PrwcaBR)d| zbnfSWfc#kNf*9Hso@cV{)HwQ_C;wP=^sM9DD^JhPYRH3|f$aj8a-*PXmgS$iC2swI z&Ry;E$jb81dsI_?SMG!k!OI#8X(xpfb;14CIr|U65)>xf@){=%j$7k+^-G0~n1nP; zQ)4ox;VdG@9a(E*HqzJ-P37;5dCGLI;_q`qjCm zuF9j_I9NB}j`W%Czz9mo?6iUWm#Hk;|1t+e2gql(nJAXwcEu6svm(+cCZ!ciDlep{ z$gGI7aQdhRk#>_lIvRv-?FIBM_~z`>B$xK)LIlJw9Hd4{B(Cjidv$u{mK=gh$@s8$6Bakf65oK zHCyf_Hg>+u^7B-6d6pHnh(6*+a&s7FzVY_^X;(tzr$#L2_6H;xx!e*2%9!=MRsy3_ zcyo*N@o5+R=~y1@#7glO)1c|eyX5`nDJBmH_kwMt;S(|fLRWz|LQi< zQE~Ia>!#w%ZjdG_EPPdMkxoBhwuZ0r3No8J%bjlv33YUY1ue;=Qp^%|AloS;xFqW2 zks2}b#qQQ~Z-)=lFDSOPqu~w=j?Q2nBpAb`O%2f>NUbM)mp9b6tYv>raZTEC@jafIzm02}|#1Y0(U5iphM#)L^F`fcA4KGz$PYtw6m z6XmxC;XqZ?jP@lAC+JX{A5FR$`=+ZnAt`M*D^#~l6Ywu%*XCf7n+5s~-L{7$>6y3s zBF7?EGws1{HhC)b`~(ERVbf}^>{CB!{0;=cc5KcWIRRd~)GpuuxFoHpKQ&C(lM^Fa zs>i|x>(7IyAotv=Ii%ZeSsu0H>FLX}J-pU^lvS}KDt$};&NJ}5KU0@|3QFK|EZ4!~ zQ(F6Xi~we)z?qnFrwzdZ^!G2w4%Im-(fNG1F+EpA1ZD+#ngm)pe}&agI`y%|;S`R# z=S92o!itTIGb(+>Tl8);V)HM*MPU}&WQCaCZ1XO*pW>=C(%>6~(293*fc$T`ye$0B z9fY`*0M!Pva1Yd|siUuW8(uguezH&|{ik{cq;<`dG-kFg?{cP0LY8jI%&Nv!uSxt) zb(hJh;g_bN6@KQ9Wa+bW=5-$<=@x%$VYMyb`Oftl+AyID#8o=@iZlXjNfJyQd3H-^ z;`boaKk;G%5>@^~iaX$3b?RjYTT*Z}14*iryAZZ1r`ymx6TWeXoHU8bp9aaCi2o-2 z+Tk5&$f1$0k=wg|dsE9pCdd=Wz4l8MMAq#TkabPqD8>z8q$LYG656!F*^pb_B5w)m zgpxjU;Q1$Im*TzM!(~Zh+PtY&b5XdOtr!>O9mzC32MWvV#-2nHM@AEDPM}8I5Dt`H z<@_tN1tjDI61h{+LK2@Iu$KhSx}j?}@I07j2?#uiX&2sdR~)d;t`MFVQngw>a>k5H z>*wRg7Z9DUWl1*z)?pI4CKY`Z3F#}Q&j>ZWt}Xh->F9E&?Z#q)Z4c~v7upLahlm0k z0O~d7FnJAaZ=B>PvG;$}8}()WHWv1>@GYrLz`1wZ;ezn*+oM}diG#KxO)jpqK&^+1 zXYLd7PKmUk0~>iN4DtpXK0F;85WLVshrD@=(a}5NB@X=NV!}OfEK957n#AgIsFcth z?_U{kgbo}}ziZvsp z0hDFBGOyoNKDK1eqH%NOp5JN;(CuN&jg4ZOR)#HJd>E0-koo_6C@t{Ni>0qx1QPn) znnYEU$%ERaFt)TcBZxH5lW`PLQzq1!w0w4Z|6vB=bIgm3^}QzF<&=$Fl{eLZdJ%SZ z$fEw!|04px&wEGHhEyjlpPQB~x@v;Z{ae)w8=A|xryIoqz9_#IS|0=D@e7eVmF$}& z3Siw5tf!{QJ}Na`zZTF`XK6J4a*vPY&-8!(jZXd+g+ZIMAGOI9n#3jLw4RmbXEG~+ zPYRuvnbBf>ToF&Dw(iH~3)x>~5Fg)4w*z^w-{UP-PeIB^x8g?9w>uGH{T^|mBEHOj zQC53j{{lY$dvphy*zGFbm4$Ptso!29HT8X)Q4%_KloWsC~M zD>XFr@(7SfLc5;k!_%6i_TiwuK6!3JqK@H=oHEK(DDxkh2ep0+|Id3q=XgdR$w_;K zOZ)s*_c|;t`ZaIOM7ELen%0?VJ2%?3x!h^G^)E5mgGsnef_8oLR9u^lYE|UepMp_y z1fGgg?*D1Wj|eWHd)8qbMvPdg&r^Bh>9`AQ5Ckmn|MYkOAj$?zaRGLy4NdBd4yi?| zqK7-aidsSj7HCfX`+s@?{*wB)|B9xuKBjX<5wS>=*gm=V7TI@S@zo5c(t1e+;9xZ< zd@8=yn})>reYvUy33e9Bq%%zehT<7gZ^DXuKP&Q&_2nC)h;OS+bQ*coHoLz*3#-#O zB6HZPQrb5L=80)lDQ3AZgtm4s6B{4}RQ>AvM%wmitzn9!ytB6Z`7l<~kZbh8U z?B;T+G{N>qww?bODEm_MHG{I_*1M5bmiazq$K9X8wQM@?^rZeM-IogTwyT1}Nabr$ zWc7VK=|-CL(y_bhmc%rEf3uiQ|7I~i&!q-A_7!Qqiq+ZK%|q0Zn@^P=LO~u-b3*}q z<*pDI;!r#7GkYe}6M)w9sZhHuOPaapAS&~VI?xw!B`yEhwOEI!5)$l;Hinmxhw438 zIRc;vFlu-7f4K_)jes+pTZeoD5VDgMrtOC>0$eBq_C?$$F)<5yUkmVxs{0eCH8ll2 zPG*v~QVUZ|fF>6}G*hTcmuN%x--`^f#sx0gr$=kOOD1Ln9=)|~brnJ`Qd>G$HT(_C+qkLO z+|`#b&@m$b|3V7Y`>|mPELw5@AN&>+^;CI+;qO%h9xoq^?s5tiaR6lFpeW*?od+hn z;C=zP9QSq#>M(~qz)=1YOG;o5(~cbxi>@sC&X?TH_i@?=b*KT-x%`XbB`MRJKx2}J zhszoYgXdcgpQu6bU?S9D0H=EQKayvo>5cB%cK!-gUaP3Bpbg-E&#wWZ zRve0~Bab6_*Ds~V37fghw*7K;fH75R#t-Hs!s{klYCUupfVonz>F~)Mi2N^OUm`2RQ{p!UN+;*cTMsO z5oz7kj6KJ-eD>XzS~mOH$+8RYJ@>`umlxX7st$@AbMyfp+V=gO^?OM-tov-rzx+<` zKG$CtxK>=OC@2UyYXy$LUGxhfW>NX_8%3#?;Qwb$i<SU(cq&0mo<=Sb?_`1E18Lxb-gE0EfomuGDH1s=t@4U*aq zj1-gr_oVgK<}^#&C<3m-=RZ2UiAJm{{J`0uqvrh+_qR^g&Q*b*iwzdrxZ|%4Sx$@_Pa4o{g`(3U22ChZ^bhx7TB*-vw;i2% z>S{mFRc6%n@L7yV8=5eq@#5nXDaQr;4*qPF96|a!>$fE^^>lGh?kbulNEC3neLu|8 z&R&{kbE>K275fW|0UhgRkc<1V!i1g92$(LESysP}6)Jr;eMiu=SI=D*e+srkq*+c| z!_Fh+Y`vV>(_eUoRK7G6uK~Z4ptz+Q3c zse`dRaoV1}57kR+R;WQ>;Ak%3q#qTN2+?K;swfc;yv}j+S6d&l&Ql?4o00Jjfu@o4 z6&^Cpt}~d(N-VrGw||^pi+V4YZh~GSiB3ZKTP|%Tw=FtF^byhE~U|UU7b0 z*rihFe8RUWetlPLd%)1riIAU?bx<>z zno&pdQKl0H9F#rY5i0 z%QrruGJMzzKkFVC$7DZ)Dq+rRW7u_7lhH54mW*9Y!uI$_6d<0>^D4)oBH z@L02*3U*{F!^=42n{M+pCcujdZkpJ&NtZw+=J5j(>wUQ>`RO^dsM?MJ*TLauPJ*nj zetrwD6;dB><4#XUsaxXEzZCwDrN&OiBNMrprq0yd_LL^n72;IX!31w2UdU0^)yCKN z9Fq*LWedG{BTGQjqFM-k6)W?=8T@#mHTrl{v%~Fs+5QN5aR&E&MeQF)@>QW0a+>Gc zN`sw!@Q^;`xV17;4h>F{M`?v3{K`4CSSv!`#-r9YQ2POE!2d!v00KF5KT{i@e0jLT zMnN4ZrflVrZ|;CM0T^7#)k#F{C&jPdXuh1fmn@Fu~iGRFxT$)<0##Gh2UysTWyv;+kHY@m-l(Hw{;WLiz_}eOB&m_9SYw5jcA}dBP%{S` zgYjdMk1;YOQt2l^G5Fj4k4i~d4(=pXnk2r}Bu#a(w)>SpzR@KAr8;aCp7m(Km(Od@ zOHFyO6Xw9cLlvx*y3)hF(i+83fyyw7Ne+t8{|Ci3(Z~T`9b01RNhFj8`rI;)mvp)3 zmsMO`tLX()m)RP4srFL4sfwHnre|pOnt&{lEAb2C&q?J0q{y*p1>__J}&I>;E?(tp{CLxacLRjk2TVRG`=)M0^KA`GvAd4^KER*eC+!!dp9B{REBjQ&G0{o8#U>+D($4{p5e3TBN5u&{;T0a z(&fM0gD;>W(CXk-B&*S0q}WjZ&w`vr(Jc~B;kY~z5DkzKYmk0;vR$;$kO563w7=j< zdaK4jPm;ZYV^MtZlb|7SXsGi$Z})U())8hzh$t>~TKLb&&$fp2b`ro`HlJDk%WeON zkoKr8DZMhn=k*j!9M~p;QmS$><`TBS4EYS@en7*V8_RUGgzs z`Y@ysEPht{y3YK&JZx}cf&2qY&;}XT$Q4OQxYU0{s`g)zivMkOtHq)aEV1#*c60-P z_%N)q_;Lq!US!ExEF$*Gd=>IWE%U|cTU3Sm@}z!;0n%&=+}2af>;|T*QJ@Vk`0y`v(O7Nr{T(pU z1|hrLqp! z^7D&TT@Wp2;*$LOsmsaTlYO5jR?n|%o~C<;w|f#~QR~4pI~g}}Q9+5aTvS`s|0#F= zc9UW$q zUk1lGz7dmyF+KxNIf=N5t+>SIR~E#wrGmf~7QeWu#G8s*-zKDX+{`H|-zmlroa|g) zjV)k)h_gOsS4F}$tdvO3pYo0%3W$V}%Gv;4UAziKSv1TnNas@QFBXl|;x8%`N%85U z*#9ZQ@uNoA=yXo1xNj=MD9lqRgSy|=*pl^1{8Fsd>7F(6HON!Yn@`y)U zU)ISFuChiGpz_NaT>G)88XB+kKkfY%c=6eb+cI}e;x?FJ9a=n5qnxfCA zA7U112tF})7EkB-CF%trDaLQOwIoSxo>oIci&D?nO|$iq^D1F!(`#Z69k;oJQAw(PFxa<&POson^u_PohRdavQ$iAc^#MrST|AXZjx6qG874u7-b%&m= zJ{?nPrHBvR%N8PvIt81>^s4q3uwu4Xy{vl+N`v9bKwL%ns+pFU=+>}lka)-1e*3E} zrx50M&uM12vWx3hgPe1idyLps-dMzUf+;loB7L&KXb<45)F}ZH0c`}e>{(3!A zaovG%|W5JJ6&!&8Ao!k9$-!s`M1LJ*l41Q8)hgTeZ zGBKj6?t7@ry;M3{Q`CkvyB(x4{yLmE`C<67s8!SZ6GgtXFeOUNVj){8>7mtQt5i_k zn4ZKSGF+FEiY`J7g$vwGtN&LR0pttxEEZzF-N}bGrhJE4ILO(bx5w(Tdbn^^#@ zql$^CuL@J<>OOClGdIx4Jg|FXpy`0iozOmSFp=J>;Mo!lcA#bi%)m}rpHuJ&$hn~0 zfw4FRM}sB$DI1^>nb=dpoyeUk1?BVgm&}H7E>1x!gRA}YPx&7xIX3a5$)4H3*dztI zCLPd~CTrb(DfM^G(=_fpiW}l%w%Cf5i8YHT zGiD$`=_xx};og$Pt`_HTpSz?GaCui%eSFo%I;+a-@6IzX35c+rn^ul00a4c&{KuEM zw>Q;}9`{1-0qDbD$)9V-KDfs~1mv}U$^HGzov+yu{YbN50V1Da_q!xa(Na-0(jeNM zR!}&s-sBZ@ZjRE~uJPKs6J^$;nsE_ z$T3Jize1Q;q`>EdO%!7vYunme9xfAq+pxA3_r;yuYzz#TN6IysRHc!4QBQzhD&mRELjQ?tE*pP9Sd>FH50%@d%Fj{uq!Tead<#-|q) zs;r~K*V4D0wj3BJ!#IfHDh_uo0BX#EEwsu0-b?;b-_7Cu0c$ooNJeKzZ@BcyJs6LF zb=3@$yyxVY%ynK&HLN^kGfvL@G4?n^eBdEwGAHML^79}WMPh;7p}}?Ns~%j=3NnvK zfH@{r`CM17_uBYNB8M`yj6RQ6oM?ml=aunhGgm4onG~e&xf+5hGbkMY{6g#@cD;HU z9=qjVGjsVDsL?n^?K&8XaQE+}g!z zqea_>iYnH{f;Ihw4Ct(=vUCcHJaRh@ZF0R=rElvP#+BxrHeG|fSvidDlZDj)1Q)d2sCcJu+-|+j@pTg)nvF~m9?;NEU1F%Y zR^gH7o_do=heZX_upPSF+hr_`&q!$tey?nJ13BH>X&e$z9=|#3TLaDdl%^a*DLmy4mo0wm5Tcp*Xa;RIGGN(F&Td`J(F7pAjea z4qEJVpy<2gM903z;Y1kn#_jh)m2vlvq}W6;#I6^b+6jcC3eBX(y^AhXGEcwW->n}e zuCZ|Wx$(#yz|L8y<>5_{!e{j}65*LY$6y7GC=kqJ#A^3F5+n(^mex6cYOHxo4BgDSo7GRB;pId13C z76@^y>JYFnYMV8$qNUG$JmPfVQe|p>StG94xHM)}Qsc>Zy!&AUWcNdLgtgQ_H0^oJn0XMA-%*1y715aUuwU;x;-{ znoYtCL!4#h7N+O3{Wr*l1|Q{T5(?Lf!B@haAw!H&xU#i!ABST+I+X=%n*OYwPaoyK zbJfl4Wq) z{0VdER6dvZQqeVkCZo$?)o`s9sm-8zxq`_LQ?|Z6BnJWet9brDw*CSt%Jq96hb5%D zB}9-01?ffvDH%XOL_k`)Ymih@M7n1PX%GiQ7(yHnkP-oD7>1Irp}XE^Jm-8r^83GQ zv0O(NXXd$|d++Po``Y{7x3%#1-W=|#v-J7kGjg{zgC>cS*9H!+ko``Q&Y)j}1E$8L zwooeQu3?dhdl<=x2X(GMnR{g>&pk0aWT5AAZ!m_p(%2_(uRYa@L)g@u$wMaDP9 zIJ|Esv7KC;k`z*L1fMe11xAya;}HDDQLYkEjyzO+FUnXbm1?nT7jXbP6;1Wux`~WY z4l#Gie2v*q!e%Z{z@D^vM$Ubdf}2oK2)+a^;j<9-Kyp1Yi6OI<9sdA(y_wNG!Indp1{y)K=L;ZAoh$iZ(*^7CoAj47IrFL+u zG5|fJ+Er2#idM(hM5zjNaT7S2CpkNV583u^d4|o{sgbj$tx-gM3m}*+3dn{(GTSXN zL05}AKjUqc=%yfS^w%!Lek$01vYKO;bu;(8>5RV<9m++iF0F=_s5~7Ioe&q)e6*C4 zc-C|g#~KEyS&w!bG%y}a5bZ%(K?+kYHg;sUeT&5^X)g~Phxr5+Zb=bUWD+f9dtvv+ zL<)a+KK1_Pny@I-bf6#%LlPN#`5kp< zoBw(N{)~6~7kCTKSJg{+125?+1uus-oo~r#ogay&I9!-li^aSkjO__N%yoEG$XWL? zf3TARc%?QtL@DScr>-RnDg52tX;O(4rY!S8Js2q1pmXrz%nAa>ufEu53eyu;Q5&eS z7FJd`;Z*YMPzySPF5yA4N6MetFQWSmgMOW!XR|SC$1`;6l+oHRo>a9Gwe){ zj|9NBdsG&rmDz<@b?ZuXUpIi?_rKb8mG#!n-*xjAKR#=?sZeyjP+T3`W_P*PREbbe z%w|hZH$U2tNJsd-9#gnbD!$_y2`sngx9~oKNaA6>Xff9_IfV{O?{MY7{6jF>AmEy? zYWBI+zX+u^JE2U&l|5KcO}ycd(Vo>UN{?=-w8|13fo%CAs9jF(!MHxcei_xBEFBab zH8f#{$|Z7~6NLUZI1lsJjoV2bal0c4?y&*ez`*^nP48=Vy?xs=ORn4Afhhy|=aqxR zoO%>7ia`tYf`tE~)WrF}5WQO+aI^7(N@L9}pnMmeB5Y##YQj+=s3yMn{J2AuzA5z84O)v0uK;7!xfIpi>CmAKZFQucQl$YPu&6tsg)OwXLJJ*0 zhREfxcV_dY2So?t0^3a&GI>_2N)y_E%Svlr-CJ#7Z+Tc{e&jzg`+TwdxM_6dUr6@F zC1>69hi*I~qjahvET25?PrIIRd$w8}mYk~}n#3k1?)*O=4y+<^9A;H8F8wzAsJii_ zSj&H~=~yhY2BALi=x!35&xP!5{^;-Wr;^o`8`jW8lTe!?I^@q{_&}(>7K?3FV*bn1 zA5)^r-uXu1sNYq=9}UBz=`Gv{Or?e=<>N%bM&4M{juH^|G!pPdKnTVcuW19J_BmCwM-Lg_I&KQ9uO(1;I};I zgBI>gG0_z3iKenf$~27XmiC5rD%jW)x=g*QbUK8ALhmuWX-QB#O7ooTIcYrO`NosAv5o=C8{!^wo(pw{r(r>$283-V_RG8{oCjuU^9)?$XgL#WceFJxjMvKIeA zA$m*WUj`+-I587XTcHi~y1XH`)ZM_P)I=wgmwAccEn_exT zss<9!6F#>MCL^;;FvK>({<7in#^+gaW3_=GdQB}Mw*%3x=|H6Ycj8tz?5WIkQG7Y0 zVnnr8S)HcUik2iyBMP@?MO|DsCX~_v`wh3Wv*x2ddnarjIzpGp+rpPNhlfBE;our% ziX0Y>kx8?c{|Y}fr}hFu8qeyRK}u^w1lz&Kj=zh8siyKUB#UKpg=vBy5Sv>fsK63? z9rR zjrJR=FMBFxy$CKFI9IL_aB-<2JQDYU&$Zo74SYlK^C;q4mWbV8)J4v<5YcGo)B0c`?A>8|6?*~>zZ(pSU#%tcc?z^CW__TagbwGzVxZr{Pt_Kl`p`QtzH2Rg zEP0P=N^4wTpM2WN(w>tyN#K@!2<^&33XwcWfN+!S*V;V;7NWXs} zm-xpLx9Pshsh+uBiuFGWZ3lMC@8y+nzLYgP3^H)&LV3EX-2lBu6KP1(Xc7_}L=f%( zmMPR7GE)HA+ob=1Rpc73yO=7xdr=yzRTboVV`n1xn^Y$=VFldY9!Di!uk_m z+vWnh!y- z)br3@K*4u=9a!8DN1G>5csI@6o-raI-puk9=(QGBw{f@d$A8O&Yc{pMq08owCSfQ4 zm3GR1VQ>TFnsw`f{xbhh%@yJG7ghpHpVmSkhNW2~JzM0ON-E}jqnpaQhyXqBGX&H^ z1QrR)S>jdRJ-FF;@_AQi?^vQC=V|FTxND=c>&d<#31De7AyI^QS~={;4caofzdn(0 zn@f|LElGm{Cw{qz+0&+(F}OI`3?xrMY^xd{h}6d18VX8O(@~J`%iq>Ro!CGv3M~_I zprr-1;^MJ#t1!<92B!B}A z!`ve3+gl@)ohh@XX>0{Bok5x6l6mw^l#U+XL!o=BpA5tMf}3`CnV3k#^4@`(7%yB9 zI-RZijucU0gQz`go73Gmdjr;AC)1Z?@@Fq4JvmFsfmP{N{7kxVy}aQvP2{@ehTUro zaG;|Maes|52onC#;ZSg}+~s1X!+1rJuQ;}=Zde(fm_3VS+#27Wxx?bzgzD@A$S&dalp}A!w0O4LD_&QELhFyqo2Qy#Q%8Xw|zb}Zly)Y zS}hnHWEI-%TJE{$o-k|0CML9J#74fx2{_bN3n+ys!29(`_+{LpV}AAJiJ-GsL#lE=3DQEt&;F&i|j?l1!5e@RkLFXLdulGZ5IB0Opbdq4T zx~;6Su)tC@KAL>hr0Ds^U+hP+b9GeNpFvmspfv!GZ%cQ zua#@}`1$!wp7U2-wD-*(IlUo1(78~rTiLq-^gclww$cyMat0t#0~Zp(IK_b_Mgv$0 zH#mJRy#F8201jJ}thsOar7W%j$rEi}6fTb5Ts7XRsH>TjZ!XuXW()RlDfXsI8&zje zaH=ue&PtlH>E$>UkpyheH-MOni!B8(41+rRS-$>$Q0&FNnea)k>TD0@81Vt-CW3!p zgF}6_X{IZZgGI$Sw+Q|OFX(hS*AR97u}hyDwbvs|^WiycI5Q`IyLk;4N<140;nH@EIaKFx+P1`zGL&)=fh-|oQz&>ZPhMR1`NKvs(t-@vcV!j~5 z@%Rm!;1jL7T~1!7E{=X`PZF|143MDL9jMF8TU^o28dAv#nAO^3|JWno7g67-Z93D6 z)_WR3y|rt#6)k7SrpZAN`;($Na(19?vX9q=qCOkL;Jyv}1B+Z6(PqB_e2LqAej#b% zd>WtnCHQ5jpznnr2rtz3-aDQ$+Z{B!SU?}9U{=rj*Xk2F_BBd!ixktl@0XJteo4oP z$0$905B!11n-wgvcDkrC<3%^ZH`^PST`8bw^L9pyY^Q9pulo*Vzz#n9LjqHoTZ-8a zZkC&cs^QuwkxBfCR>T`G?ks3RE1#N?f*U!)d4N=6W{)?q>9Tszj=si0q*{mi+KOll zc-nF|#{PHs#B2m)3K{`KEDU9%c#(t=T!a@FIbWc90xjH4x9e)u+;-q@K5LaeFGJhm z6?TjCx0rzGtxqcSy5x$U7#GOOx5emIMLT1t{JiT5l_P|bx#WY{Gj#@28yvTWb-^N^ zpYd%X6z>fdxt|&x%E&pp6bzExlcqqUmVhngS|p$=+dAHCg+h(l>pY^(-Kb*wA|z_l zhyZeEhPt{cpuGG@E+(Hz9{=`%ts1>0ypR0IfzZE#ORI;{f~ji10=%;a z)~Y@R?aI)hC&}zxXck4>#F>I9)}BQ~5NKs`89F{F@7{cTP2*t*|0p4s>FcLj-U_bd z)!j^@Hz)I?MCuW4dI-WcK4y?>LwzaYae=&q#!Ih|<*|NrS`Z;_C2r-qX45Fptv(?B zSLms0HVN~R=UCCXp+OxyC##fT;G0{7vXKNX)obiqL`lY^grmWJNQ^?6r88*5LNx5Q zq|m*LtLT(IQRvNP2Os&H4ClCnVOU%m$W)*lmno<*}@~=o`Nx zQuBum^8)YA8}O*F8rUQQITQyyD=YB69c_8ef8PReNhk(@2Ee7)S(m%+#yIwanr0XJBZ^K~fMl^co{;Qo{nJ zwksQJ;m0?We6-=(LMRr_mXddIazjHzN#Eu9dXFj8`-l(UEaKPL7Q5B6kd>Dqr)6%t zD%#})bUVs)A8fI+}}e*+Md2hBS1~R*T6wJ12GSGbbE7f6dvz z-*>gGT*rg-$3e{Fz{4p?Kn~yO$kG?H&;qoKKtW}fEfNiZ5im9Nd-t!C-FNy z{lU|c6+|sBVwW!kg_v3wlfdo(PS1M)_kRQFL;avKdp_>y<{mm5Mb*q5d`mZM1`hTE zYo`;vJX(FklVa|})T05c&gMEhRwl}{F3KU{Ky~wmOX3h12M32)Cg@#$D9-nC6Tna> z1|XU5&t@l_fCvm4baA5(J;!w-vUfh&6|7VN}Q?Q$km+%yvXO2lPDfY*rndAeIpO|ClClMaO?^0xZ}f9kRH6Bq>oIRMqqVwCnjX_y~__ zp=~M*a*Yd*jU}?d5s`6O4aB3CvF4RTIhT!xhghgaRkwYt=3{bltvcQu+xPm`M@Qlz zpljqBZWRO-+TRR!I?Rka2OE7~8{BbqOe(lg=Zew-Q5Lotxsy)?e@W3Alm$b2UaPo1 z07cnxGgO&|I?9m&gY0otW2t$`n_Vv&YrzW!ZvsxZ*()yB?}tOh(WcWEuQhP!#LXQD z@a7aQkbW#4adyLWfIvvu&4|fi2bzJaIsT6(6ALJmx!R*T^1q`|tA~8kKWs{KvWt-d z`*(*#C9sP-4$5Kn7{y%E?c8T`(@*15JojfE&U7h&9W=t>{)fKR&mzX1Mfp>h-14vO z)16tbwp9qu=Nc89_xl4ko$RaHBzJZteMe7@Upj+UME7&Ps$YB;is?2xSd5LL`6^Wp z@O&%o_#Cd8*~I*tw?hnsGSa=Y9{4NdV3 zNK0wCIrWZUL^Kv(y#Jl=1bBZ$2jW|%{(Di3hwc;sQWbx+fRNy^L5jMVt@W^kx~Hov z<-;YML4RS$=BB@qOVmt~0>v`{YG#@GTJWX;5V#d?T!&sW=-xWU{`f?O+@R^c{~gt` zO660O_|hZYHzB_746mW4RA2wLRWG)0Jfs%yWnO!Z$@{p4v*Nck>LtKV>Kp{ZbGVP7 z!1M>#%_~j@gliCRxy$8!1YtDOF9%ma)X>LY9~Fw^6cn92Qq>&l8p1KOCx0aqBF1Dw z-nP>K=2i_U1myH|HBW^@-UCD@RR;!EM2*`IgrQ)+;L)o2R06a-SGxT54%^eJR;`6y z9i&BFsbP4N9AU8c@2f_KNYSJM6{?vwd~KS5042nVUOm6S)Sd=8A}r24p`6!ND+p)D z69@dUdcq4~u5keSJm7A39QdL7?JH6olqN2Xhs$QMSW32F?kc zmCy2?8DsXw%k4^NjnHwdQuYjFRggq!E7||1p5tJIpZ5dRw8z2cB!wAld~vP^=xiX{ zv!rb_S)G*A=7{SR3fvPNH|~y~4#ls{S^AH}7=r5Th4Avb+-%X+aKiVfR{_`ClLTE{ z`2J^s8yUBD!~D6LQSf=I~!Nc(W}TtUZ# z+vA)vVKkV|w9XzuMy|1i6mM0P`Gu(}f>{zvH&{v}W)&%KmN(S_qXh?or;5A|cv6h%{h6vEYRx*#=yk<(M}bFP ztF)_6Z|c=;y##FX^}pdKwPn1m>~+?j7VX$D3D0gVW9ZG~nWo9`2c%lDjav&FaAsIL z)rO}Gfwua93ulsYN4whM(*ti~Jx{;Hfr=?x5pZ#>{|Lm*7Ix?iiozYw_dIi2UY@EI zb1pTQZFgoL^~6+#UC}C}=rq4Uq}L^vwXlq%v(cT_)`5c-P!Cbhi4}5}`n!`e20gG| zTtSaXMh)t$Y%YWGFjewX1ZhvHx_I1+(s}fLqntxMpqb2|ja)Z@^!8^?@y@3f%F-8beEj>OsXaxb>b`-QU3TA?VHlpe6hIeYj)mQ7y zebc}9^I8(eogjXA!nwG4f{(8x1|T{~xhY z1UU{)BxTL`yuo-LxvQd2WNxVqllYoo&~pS?y=t{XG@x$%v%=TbS62wh<`Rdnx$pXI zhAIpGl6@Hh=tbuFUkL!&_M)Xnn&txnVI}ZrtNrv}-aaVL0v1?brDna#%uHTdYFCJQ zdH?*OV%}uu((DByD~nfR#s zYU=>f`gB}I&Qn8-AQ#&R=guwa>^h7(JJ1I3q)8$~H(_Rnlzq;&l~}@gNP6?-T_mpZkDNO?JyIq93wSrCy;r5Y8M=7Hi zPUO-9hswl)&F*(p84C5m6OaLW$dXo-)GtZd+@hpYfuZWcI<5JW+w8^D#N0yF!^pi0 z(acGUh5_RBFK~Nq2rXp4qk4(^O$^gN^kjMU^`}F)vb*BzUc#E3LF4Xxn>n^}ObRBs zMIx@0Q7q$4xkcO|;j#(ge9b>s-0;w~BSl$&)bn4sr>l*-%}_~j`WeP6pKPSSR)|UK0K*&hjwORCx9=6Gc%aP>ONETek@*p;z<3EU5I!B_6L;a z?%(^LECo2iUFAfa@1vt{CRe6ghr22TR={TYVyHYI|Cl}?7zQL^&%_z+r-$Apgs=XI z<33lrI1Y}mq=+F|5sr20x^*h5QN2A0Uw!JShfvx8@D?vV3--)ze?X2?;Qyj25>k`= zcB^ZXpj_}g>zlE9Wa)tssPpGd8mAh0#8+ zqc;A2aRq6QDB_ar#DIi$X!8AQo}UF4vb4RHK!&&Qbn%&8`DW9vVJ((qAP4)$63456 z8&t_W9I5YDJ*YZJKj9DNOtPE?{odYBPM7(4tSBe(3Q{_QT9Mg zMAiC)IYAK3jLGZTXhRA~Lv~ri=v}@bM$R)gC-O&%4ho5@9bN*Q5`H^_Lt0uxxM?8J z&CZe{NS?aa6bStwS-G-ufcF5o9V?kpiTxw@tj_&NWi7;Lpq(ACPT(Y=t9E47G`0Wm zpJ;uRz4_%KCvzs2`yG{NF~8hRj+}sTRMvBfILNGX{tpUXXVFT_^Do zG9TkXMN%;=eV~pho-lEpee>+Y^n~nFK#$u!dB{WSKY`S*7zDx{c^Rd%9&%DlYp(sY z$p6d`P)D;*;tN8}{UDv+aVr;4=w5BI7RR~x8_NzcKzU0J84*eT1yUvW?nM*{i&R~1 z(VcqE5bcZm*7k_gk)mdXcVu1{(n%5h){-(0xV@?~L+g*H;Nn;tzlC8Z0H;*RH7E@{ zx|PA{JUrfB&R=0?A>2D4egns7+<;3kW}e9`g~RK9Hq)`$BYTvPrndL z3`5-H$aBJ2Z@OZ{!t=KyI}iGdp@z>3XeVx^XH>y4*m(-M`q++skTJW6?>%b`#55oh zA65r!$e?P;&8}aD&zAiR%;X5g9^OnQ47%(Ha;47x&z!yJU5t2J!^44mz$si7)r6mK zB}Xpt_*wpWe*+LNZ)i}&QAb|`Kd^IzsJFT;+(*;@*9#yEc!hy61O_K zyL$CebzjfH-c9w$U&}oG_0JMV?}De_h|2yVq>rQoPJB;~crhq}uEF_Gb)b2l*PSv= zs~!f_sY)kH3%r;jM|W`E@s@!rAk{-?jo{bQWi$jF9WhUOzoLS=o{b)1S@p*r222Zo=ErKYsDnN$l$A}L7K4b{(GCJQl{2N!kmXJ zgTrYEjIoO-o?*YJ_8%?fwtK^dsWUN$&q~PL7jo|24}woK?P~$aM=yIqspn)Q)bB-{ z5tL^>_p{1rJ{WL#WVUtU@-k1?nZ{v^8qVW%z$j!h+lxX`BcjPg7w!HZt+gMY%y+la zI{^6wCF<*=`Td-YZnweg8gV$JdhC6m!`m^FG*BY&u)5@b!LaUhmYTObfF>HnQRHNa zhR>%09}RrJrCIQW2!qNBFW;>ypP1K(73$)87DqXeQJkIIM#>CTzi(NkG<^y<_5kM0 zz)Z3$gU{aP+?1Qx1ZBgXMRxfM`b{Que{(rY|IP3ZEwk6kH%XN zpLL;sU9c_*D^+KN$Dj|EBlX|TtQ#v^s+wl&P=8y*YhHljc<%v8>0!a#fYM_BM{7H`h_m*-k-lbYhtS%+Kln5FnF;s z^8CUV>>XSqKFlYIHW`PG6!~TOSY-H!YyBT8n_UeK;?#?ywBIH1(9O)YPWCXoZPjG_ zolwpQg=C2C+cDjgAKQP|I7TG)(DXAvbttOvKKZ3)jq9<8lCsrI|47XTTqxxiF@Uhc z=#sb>knxy(mpkf?EIMf9e)aB6S?0~g%9ZyuVx*+h%)v38F=8RXN6vtl<*Dcp))`fM zf@l|km(dz^M+0zxT{3F-Bo%`P;@~fbhZrcExEkWJiim-%E%O>`ikf|ahE!eN)!V!u zQe;jRF+L4fpSxyo$xyl>LJnul%KiB8*qdMCCfSTI>qJ^Ne0vw(Uj`R#RIxIj) z2%74=mdUUpKZJ{41?UHvolLBh2s5@iU->K=W=iB<@Kbd2->t8kt#9%M8tHnrZb|>K+r0uyQVGRxB9Ad?BI&z7* zm7hPI$_4%W({YehPwT)arM}gck|qw6kzEK~P|IPFPR@COE7&ljDL^(*NCt9VPIc1; zW-Z?mB+x+O2J3!?aB*bR`j)|hXB?!-j%7Q2Yo~dd^7sVHP{|BJ9sLjab*Zx?)}+?0lyHG=usSNXMhonu9+s3{t7J z4zbFX2&-USI)iaQ52P}>oa$ZJ-Zg*0^=i01oCHiHl#O!7K*dtE!?DsR5J-SkR8%DW z&m=3uJI+lP8h|IRE<}bcpp6QDD=EEe^ov!yr!jwd-l6s0fTfViwfv1KudF_0@-txNT+il}_{q!aKh~k?A=G ze}{^z^r`RgpyiqOO+wun0tbdf_lBl72Yz)@eumvs0`(;shn&V)91P7mI2)CIgTbGp zp3W?{^SL6V5xZ51WLdfmJ;Mf}aJ65XPa1~-n<&1MHd__hprDX!Gc&x)+{OLoj2rkE zebg-vv06cZk4r{nHkL7v=9Ls!*2wt?T6Xlua`isV&r zCh5L?88$!*QfWn@eTX4UPrpz4pH+{2@?m4i&QOh|fQPF#kLhK7yWTw4_Ado(xA~bTpU0^rwM~ zPjMGIKI-gQTo5g4{&^Yl=7Yx~NkuoETU+rF4IE)bT%Vuqh*Y=*=BmxskUzOBK~c@W z#a&Vu%Ygw^+%B2g41xI@Qb7TyO9p&dHlLq|K^Zg$vOCw$GCB4KOaXl2o>4ApFdv)| zO6Y&a9(>eZR74Nd^-R9tTTM7ABdvN=vfweY;kmgRtPb$^{UK4!Sqp-yXxUfXe_swd0` zbs#g}?L!JdbzZ!vNwR$1sF@$6?5ch1-6KT|&Yu;nY-2z@;>iv=uFc90OKDtGxPv0f zx~(z_m=SZ~->!(|(`j1NH?*kBHiVa{6BBOFG0TW6e)uvq5iP!!Rg^W!2<3QVP0(0} zeLTE%ApO(hQM~c(bg4-o4sg8lW{Zb$^5XTdFp3xGl#;P`{-AH}OsX3i&oX_Smq-?) zR;BpyGthE*crSh%EHW z@71mR=HL_==OaGR;OOjNV3&ec;?RiK++6<%yl)z+D?w+Vwzc^yyZf6)i8Z{eQ6Bts z#WZ_c3Y+BZY)Po|W2aQ}Rov!t+PZoLR;sCrkT%(bLT^cVK-+7n(tT|l&cfA|2e({K!Y8v>vpC)q5tdJr zf-BM#@78VtALax{*iF)Egxw8_k95SMuiZuTS z29t2l*fExGpzseAsQC#?MNJ$U;V-WWkBKu!YX36=y>)ftVc3EO;ijMs3{fEpXGhSP@ZlQ+` z`kwIp`uME?AWgx9*F5iveS%zgKyJT9n+Lc6-n}pt426vp9oPCOSn-f89XuX1hrt^T z0Co*A_ltNlizxu?zXty2|0rtz>DIhb;z6_*L`@o0pz}(%bb4ZM1dw|2$--BAdy8~& z=eP;z_<&-tf7Nt1yXX8C&}f-D+k%baTVFRR#CCLyXAE1H_fs<&nEEjM{!{C;f?uh@ z+H*HB|B$|O%MY>^9-w8RLrX|X_|ew>@YMRjXCA<}{Yfgak(0;DG+OWWI8Z}mNErov z*Oq*5!zt8wy-m2mio9|jZr5J#CdRkFT=nhZ!a&=z2^H-p380A>0BL?(`|U zdk1|vhvubeYIjuu9SAU5X?c>S?8xKziP%K-PGCSa%At_j#SiFs>T>?e;tJA$HtcO4 zlZj_;eDb2-m-m>PH(qq!*|)1tQ?7-9;EQOcM8Cqu?kr161}1iCJF7oQSN2~o5oi+@ zPv)YEp)l^<_ovQ-b8TzngXu}y*+f2-Q&Q04wqEWcbKLvo^bpPO5;9E@{u5z@I zG^rK-nfBB)G1FSS*~%eZWXB?2bsn%k$ha6#!{gF#NX7y@HkqkSXO0c{YmRsC9$4hy z+E5cRXe!B1Z-N@jbVJ($cRalqk~OwgHopL;hBUs_<6JZje;nYO+&rWMmg=Ye7h?gU z&m(D&tkiu=``q34W!ZORfZ|v7d)m!Iu1M9p_!8xV{>k!7SE0 z)-C++oGiXDyRZ}UkJF9;qdJUQ*<5y9Cy1`xs04#iDF-1dk!WMqf_)PN5m ztp8$kprx0aHL;r2DK%Gr{gCd|SO%MzA1JvuNl58qATN9s_)-IYH~%|lg(nt5>i)mY z@vAvDOnx~~@zY}Hns55U@PT$H%{9u97Onu#%IRq4yMSDDab2+y-Y`-GG?MGiZo<<5 zQPc4yGM_gj`Hu;1-1!TMSIcCeZs4kEpfQ$OZ%}#BCTjS@`IL3=qe62a|1@TnpR5rt zv=mAu39dlsm)@_!P6GC71s~H^xdv>E9_)vXJ#cZn*~ECgAMx8^olubT`{4?18EV3i zjAuZv_G$Gi%nqwu-C_2D66(M+iktGl8cv_`J&e!3#Uswvlw%}77KsU1(8AU}49pWB zm0&L=LqPvPhHq1CLUr2z5o^LSF6b~CKq;?8a}lEY!XQ`ABcOd~do3%cOw6J_K+*^b zd16#}dOn32izmqT*P0VKoYjjh1SU4`95lsvcUJ8AN4N5(-S#}B>`0`Rk$LKJzmdw+ zanRsf2|2Qj8Pz#!|zk(IW#{tkBSS<8{DF^ekV+l=8ZK z2fNpdtbZlXAzljP*Me3Wh$KIgp^N@@L;%Dc7brm>Qc4?;Kas%v$AwJLnPl)beXt_T zVC|3(=-Mv@=4;~N;~yXQ1@|s4UL2Em0RI@iz3ncXL6V^vQDxhA;LoyBm|Qw9mC>67 zirwB?mp`HIFHF17m1GeRkO};zjje6)9(-RdWaqMPDod=xd(0jZtcB)}A5(vIi!hN2 z{;1|_*OP_Sa`eiF>^Ir5%Wvv4(oc`Ey(Q@PvDUw2R0!Rp_q-=UFV`@2~t$ z_-WJW{4t5~#_NP)lb_?{$INh*m;wD8>CrMEGkI+Xr?({PlHh6u*53n6uwPvBL#RRE z&iRGJ^*yS0nNZFq6tk>aB>{p=_C@UL1rH9@N7lV@)Lt_9r|SgPwkkX^@MRZRJIllA z_c}aoXq1$0Db1vdCTEE4FTQtGBEhlNFSyV=2^uuS^EI_<^hD>_eIm;=iPar?^P8j> zw&u0MKhS70IM$9bFSJJ(bWH{{5_mpIkGNGZZbu=%ux9Eg(33w-l@XA-QtvjyTzc#M z(8gyuIZ(bS>(SI80mNH3oM@#>T^P}N`7#w%rh`6PtFt130mr&Z^@>Xjo?8GEwC(Zl z39)-3B1#qn7pzr)5lUybx1YQyiiwFyPf|OP9(RfjU}FWpJAcBLpvI+EPX72tuFfkD zDKw2)d>pqAc zV$m7u61T4`jOJ0*<9eiX<921^!H|O3vrSzSCuO=q>IkPABYaZ_Y=Y2u7cLIw8~Mgw zZTi46@LMrQ`XQ%=!Eytqet!?39*G$FD1puYuC1R3ym>Pn|?_0 zmzR9+bx+bg?2lVFL5c*iIua?-EHm3!!MuFAUxx)8_(>R|9koXkDM-W@NEfUZ} zSH)UBfh66-f@9nrhb-1^5c|Nzoy78cs3TQyzL2H^v)EXO>zOq{q(1rM8}zbJmJ%{U zp)Tw9!s25w=ZQTnLtZG}*zEVJV-rl}DdlyzY!>pbsH<@6by4=f_j{2TUOAJZ&;FP% zVGI?Pm1Wzcr>Vs0U;Pv)7>IXgEK=Pd1i4M$uf;D&UBRSm`yH zV02Do{YF}4*O{R1#YcGtp>B?xXd1xTiS@XDYxUDV_!WH&%PPgyd>0Q%kCBK3mK=K> zn2{IpgY!KtnBd=#f1sJ@X0V!Wrj1s-q@4B#F>_vfI9~Kb&iN80t#~bAs2l@pw9MPs zFTh3%XIrKe;3W4n&+pBEAuNWhZu^8Mob=rd9gip;xRQTR(k*|)#inqyGbUnROIRyT zpel?T#Ss-CmCcN?H1R8z7K>0W2JOrS)&&bfLc>Mh+2q%Yy#rpi{FgSEA#JpfJSF(; z>@U0fwOD#|(1QHC%iii@j{VHtTo&vSzoPW1`08Kve_{d^@hk|3iO@yg2F%S1x9v+l z2La(OR%SY9XUcEP-D?H6d#_9~E7bMsCIPI7wC>D{AgoY!_PZMDUTmh&GL<;k+>sy6 zv+XE)(nL<3w1wJrFHWeQ2Fw}tPUiYGMVR`Lc?|5<4RErcL+$%UVv%z7hj%zQNRaLw z3^%jrW*3DOg&%&N`SWcDX@8Fy8Q3=9OXz*kC2JIsm1XCmQazSjHk^(^zGpsQC!o#s zBW!s-*yhHmD3YmR9yI{hp+TQKIz`-H2%{AaB*c!p)O!v6a6S;v`b|vC9V@~yIq)2uYB38vc+pB=%QRg1Wl zz+q93F|^ZvE<^xK5c9L*3zbs*y(e30Ao`*}?aAoug~IXLQDHiHV{MH4C%D= zm-gMQf%&R5sJKM#7wkVqAke=N?=bW`cKdqQD%~-8xe{j{wyP9QA9)bJlLR5tgpeGq zB2QqEYPww;i{<~v-NT;!&)s#;LONIzX+rgRPmw4(R<(2vqJtGq@{+wz_ToY<&>QzJg7)h}_6uuqN^Or(Cg(xox*9`YQ>96rY< zs}-m}e7tPulRFu{nZ@uGHRM3y0wc**&*`#0y5G168fVR%8e%o zoUNj$`DUr-Mf8vX3c$S^-#h`g>YNsveGcyA-O~0~4+{b*y!;CipBYNB_B7kj`xuA9 z)ZxaT>Q&Mi61|&R?1;3q4qSpU{s2jY`t{(s6psDw*aRaCht|*zvX2$c`Z9An7 zlU1#}xnj=JHE$8|<2|G*qXv00Uq&N(-q1sRYAgb<7qv)z$_^wa^s#zL45>;-E&Q2? zCMOj@gB;vERMpdoiTkL`iY9x-d;q)bsHe|#k%r^RV(?J0HO00de|m8RC~zuEX1@6t=~v*$`7t;bUr70-`!&$s!U)+q~4ezb! ziBo0_)_!+gAHUBFMf)~P(BwTh@4oM)0m?o|P_@&#wp&f`!b4Ava_1K9=Y%cT-GRr0 zB-kU-57VPcWN8W~pVxU43*TUfE-`%8OJd-J{lG7NSvhG*l8KipJB#bAr{cHPPR4_T zsd~>L2QkJN6_h=Jv>eq0tj-Fv-bt2wij`{c+n} z_1Iz9I}uE$F2?Rhz3aeY;3y<*4)hlqhEzs1Z}yu9w$}nsH$36u%SiG5DJ=)*XsHU3cz;YBO<(mAe(ceCPb#xsN|jKBofHcUj*y@e#0{ImV)Y z|M^Bs27y6AY<`09EOB4Iag!W#x0*H$QCKm(-4hA?h9s>P<=o4hBpjOMM8X!Qh+n#Y z#J7wq=v6riDqP9T3?Hwr%MXD2#dr~W6uu!cEc32oddyp@6LN3bxz)zB>5 zUrFbdU!E|Yp57<18K$yb-t;@o$3y}opUCLA2n{4=PvFfvYK#t(rfRqKUWJDPAF2L} zRGqWxlUvZ1mCT(w({QJq@uyHs%)Otszvm_VtmQaqPlNPmU!fywQDj9_Gv^k=4W1e1Q6Y{yCf4gxMu40X{CBF2dQT%S|V*QBuBPSH*I*2{e|0hP8I+30{J)Dc(-p53u z5!;06GGa#vIO7n~&E{1LVf>__joEIgK_N!1(MLQLI1&qqVhn|-@}g89rqVm&xUVk_(JI+`>{6>!QE z%mo50j0$)I?vel1ZPf=7hBKhW-rGQ$8UWiHAgbq=$d{=zibOR30L7?;E+miuV?FwZ zi;C}wfg}}_>VoKNYO>FJlb#e*nuykW08>ECU%dEaa&4c?N%Xx@qOCdnRoiI7=7zeH$|b5DOS@uE!ALc3hbGdMW4J+fyoGzUiHTiL)Q$g7EB` zAoYRx>|#u_3+>?6DvhSRmDC1#p)kkWe2x)-;~l+DDiD1}Zoq)(>IZcQ)rv-H5JneY z;r}a5_&07yTX<0yNKEvS2gqc0;ZzGmrCmw=ESY@YG7@YrkN1IDLf(F}T(h3GdEMU0 z7^KWD2Io=q7!4{nHZf9$|1i9qeqAyG`QUxzi!gKZGk`OGGcvfuKTyO1uIENin7^&UNRhqsQgc}*|( z8u8Lej_v-*%wZk{*Ly5k>5w%yU}qSm|I8o!4?3}tSvPz1>3-lO2OJoCXU%6l)Q!;+ zJsfd3mv}-ysMAFjU#8)EXw{-|ZK+Q+X@duvaVzsK)zq2!){}y$fZ+YP-dEuFO(UY7 z*uvw@o^p>jzb#%XEYi5nWkWE+{^Pd&vUdl!-Pdgdu;uC=wOT>$ql4G^ z8uo4#tGGw-CkDZLZ_7Z_?eiS7+EaP8?xY`Z%GqBeo);Dw(2ub5uon*E77BL__cXi8 z^^@iV!U%6=+|uM;)@M~o!%)Bp(bYALO@!M}t3=d|;d0a*s`*e0f%zbz0BvQRei~<9 z*Mk2zZl_Z?yWmfSHfrUnNj_ows1V{0eB*+ikZ}lLYvX)YLSok^C{y38W;KsMS~!|r z)^zTOb9!7)yshWn5l>d!1FG}5uJOXq@Qq9lJ>2NLf;JBb+8>l%KSWcwOmPP6TcYeE zjJb$+tHSaL>%6VD{M$q`%ajcqEIr;T^Ql_8z8dZ30ZyKbQ$->o1^g;0y1Zzv_`R=^|qlc3Z%yXf{*4f%_&f_6^Vf&9+f=Ua*HA zhXe&5cu4>rGSiZ8=$VE6G4_XZo;7-^AA9_6ZLvd4UC4(*uv)E2sx9doN1Y(dfvy*s zr%n#OdhigBHN!QYaJpUGEA!HVN#E4O|5#To@OV%A>j??aSmQk;A^h*|ikv$l)iwW! zvn&!$XG!8HxFr)8^5e!Q8^hkwqFBy^BECy(wo!mbGJ-AFp`fK!B3XtXd8)|7Nx(ZW*y53*ES9u;GV)>eSB*K!I}hKvRMqFPi`)gq;_|a; zmk$hpe0g^y7I%*UQxyD{PY@2gF?fI&j6Dqq`V3MW6aIKi_}Qy&C*(K>Y=!I4!U7~~XrJ{p#(rTC)8E5Qh@ zG4o?t{1OUxL{L!jP8<+;zXuRfqfvR`nIK^U`<*Hj6N?uYZ*Q`m0I!ChPCuEh zdtvdcRf{{$_6!*3=k|7(FmlVl;oyg#wSDb&F8As`TJQi(oMq4Ius10JGCWEN3D1il zIE8?t_4VW6o9|kq;uD3W<@8XIpZm1dKFV8LiSFU~!{wo%SgW^6plx++Vp2j1Y(mN~ zqkXWM|6$=_zPM`kgbw>lvB!*zLme}PBhNRp&w7?F+X*bn{NINd@WKj1>Ikp|b6#!H z=@mafQi?jJO4Su3{40c}1iwCSO9mw4H5BUju6}?Y-n=NrG-dFMVXQTXL8s(gbKa-NE4ITv57t*)=%Qko1ZszjD#28 zzQZG6nsjy9$;uHDI$VFcLY3OOA|W5Wt0#4P2Y|x!&t*z6!K&f2^KoiV7fKkK3;o&$ z!?dN2r>CavIx6l<|K$LL0C09+s(D5o_XL-~J}1gghJ12}UTzg4PB%VR-2${8lhG&5 zt#Kb;X`dRuqR(Z1Ur$QvRt4YhJ?lF4X-^R;-%3LXImq_Jr#{Y7Qn@h^zQp}A?-?{^ za!V{d?ugXP@cDq%?WHDNtCL+J^+Arxl=MBY>FRS1JsS)bRStFUru{j>(KMppQcWj|~j854E5l6n5^MZDRBmWq!yU zbI}6vS}pA$`phxkbl@hho2CUVN)Dz;i2>P0(S+x(wqpag7@nY{v)^&5YUN&|trwNv z*I$~dnK!dL~dTQ)_C0pAm zlg6$PUhSLnfRu2~sY3x#0eF3+yj<2g4D>MSfhS9rRhZJN)U%%Ro}A1)QV&8{8cn@@ zPOF#+^e#r8LkdPp2Ka>I%|m?4d*5TLey~>eE7v?U9q{>Pl;JiJJW|uaeJSQRtyWLd zT5z-;^lVcls7u35W003mz_+cXz08f{E9DMt*s+#ABUoHc+0yZ1Z170=W?f~^e8-R} zx-5_B6+iY7FpT^Fl_gDitlJBmeoi`A0cPjf%f@t6|CdZ?2d^DK$IYqO_ZomNHw;BO z|4e=!8EMD4owl&CSkhV%IcW$wK@c2Ebn8Du@IxGRmMtcZ=NgyaH70!$+oM zE{nXog>qdz zS50D|tW8f`-B*+H2%&94Ce^3jmwPU_LO9tXtMY6lmTBZK?cDHG2B>Yk)9#nw);sW% z!)MNnn#UvnmV3+R*?FXZDNm@=>C*x~ryoij>7ln;)8faaGCYRn9qHv*Rn0IHFZN_{ z8RBoYCJUg$Bv1Lzj39bJ+~g<&l!eW<#t7QW<;|QQoEMguZG5R_LCk_YRkWi(f6rZ8 z@Hm6dvrI3j{BG441URxMRg-#ROZ6!}pqM(*z}q%=db#q}``zOq_ulwod{+^kaFQlC zdh@YQ-0j4)63dSiW{$ z{9Xw5%~BIhh?t(fLHZhn(}CX}-%zX`ml6}_ej8=rbC@<6O0-ncfIN;KE`!sX0~vO* z177C6&PaJT(UbOZ^8L?PRm$0%NmfAwv^Hq8c9XsoNT~2Divt{daZ`E}67*>B2CZsj z+-x^M-G5^$Ttq-KlVWjw3NIfO*w3vbfKtTd@AYV9eT$607Eru9*^b23Bi<87PP=Y3 zfedhl!@h_WJS%gyrOgbjqL?M1K*$l)chZTu&y3~z9-(FNq)4TuW*3%d!Q5Weugzeo z8>{RzBfv}U8TToFgY=Z{7nA{4U)K7yJDJR^qFqkXrMQnuvNvHAxAw^#l0FtMQ_XA{ zstS+$(M5lFDd2MA5wuVUs;BLgoZPGhO^Ihv@vxN!>j_t~*kIVK<8#Z{;bFmwik6XV z`6KBkv5n1n(TS&z|K!d6oCNgq?O|X9-iGK@4O|zU-p%{(zZI|f&d)n=m%`3-r_tO)H_+>qe-qNj@ z0{R|P3iQy6lFq}_0#v%NN#HSaK=+(L9L`8^rJ4xA}E++XuAh{uc@if-LL*W z(f9#7uZKlPSc2ITPG>S<9l~$9^kUYRq#X)IyBTZz!Y<3H7nuldF{@sPjC;-{{~~3Q znEH!2$XZdxTjM7`c9}JPFWUKRC4uo#CQ~XTD#%Q9LlrFz0%#d*<12_UfcjasuwR-r zDbcfQyWO>_1#th9%DUzF!tpz{;7@TCrzOn6wdf3xvm#F@daUK2J`i_%5S6F z*y3yGd&VXhi;K>}zCwhOLv!eLZpO>U2Ji77rxf+QN!~Dg1hJ)Ik%o0fE2@3;ul+5Am3LZQ;V)C2%68+we67@7w(Z{kzLPpAAt^#PM zGvJn54~As6_^flE)o?5!2NP8ebsgG@pJot1XF{yp9b_N+`RwfV9}cYRr3S13MsPOC z9VcMn_!k8o24Xs=o5hJ8=sBU20v814Rc8R@nS^L3>XRe zw%yUWqMHGViT`6AQN(Yh;etpW>qfp)tO*W4zz>e7vXjfL6AS{fCR64acj7)*Ul5ZE zu&fx~F)<}QYEPHCy=*Ia>V06Rq~d+*`%yA?@4&#wXM<12)_^^lNNbzGD5I~~ada%R z)hGOSi!`-T!$&jq2P(gl2O6i&M?Za{1BwF949>m_-wNvZ7<$pd`Jm=vCr3%y0im|M zyze()GcReRE{Ez&bJzK9b{()Jm5oGS_Qr72gfaw4&YUD#N81O!U2Z-(b}Q1=`IW0j z9I{Ei#J#sWj`qtggbW**Y$f|b!$5KTiDEZYju%e_C_N@6ZqZ1}W(uW%JHPR4pTQdI=0@);huwhb`?*e~oc6QZmJ;-MvFiT* z(IS3s@$jR7iYNDZOv+0zdu8;6RGev!{?z`$Y^D!VV0O4E!@52!wYBo3ysAp+6iSGe zGbtmlw^@?`t=wEX=5V39@u-ZM^^%IU^^=f-TLipz~qJc0EWd+&$m7MYd{CMTi{$}k||KK_Db&Qk$TM1ZkV zX4~c4e1LEFmXr1om1>(`rZdybVa9HCaqawPwI&B{Fl@A06Iv%Y8=KH=`?F%3o6|MF z5tMA4T|1=Yy2*5b7zVa&t?{sp^TUH|*4SJKN1TS?nmJoJm2Z|oPtbV#tMIYS+k%{a z)U=mfdSg3Ojox9@fm?S5Ug-hHG`Hr;DmHenJGKvTx7EUIM`>W0I@D#YoPlTSe3mEP z5s93PrClPKGgcQ=<&JW31rIrTJXTrU0EfVlIF94(z|Wt6fa&~X&R(t zzC0%Kjk!>YE!`+=nvn2q7<2sk2P~1{r?k*9j1pM*Dz>rn_%ln+AhoknJ@`9>0+S(& z=h3&fNZBdoQk;T#Xl0eG5<_et$Iy^&?vBD;P1PYYobl}81CBT1Z}I5>q2IG0z#2Pn zfB>~0*#^jZ{Js-#3fNz+I@C85(!zL_H^iO8%j;-miCJ)+xc9?@U=4E@?Gba7zXw}A z$}Wew4yDE^V)~_k0y)ZibY0PcdN?bvCSa6?xQ&iuSq^47+&6Pp((n?bz_dSb+mBl? zZt&|}heh|9ZQ&a1>9KC9G3tOT9!4#AnSzq)-Z_WyV*G68c<@r{`IBQ_hvhvKp5YOP zCqFrS2LxqEnGzH-^me)z(S^dLP%E>T?wpzP(#kTzj(`mkxPa*KW#M4HW$1`lt+@wP zt;w&+)mby_dZy8iCvo_+UloFo_Ro2w4a`4LZ-9_uYE8ZwauG!|?Igt=~QiS~|T z!>e!<6EFLjmfd z-=rlxseUkh);Phz`9pK9RZ_6-K^5Q$G`zPdZ*By*v>zu!QZ3tNOnEu*J5&pR)%&zV ziTcVXjI;ARR6omRJ-o*eOu|v4hC3cXVQa!aQKQu^GL9fRKgKV&P0FL7`3r=OK9dxm z#oM`Dl|0+KdT!%mJI}V!UTUi*1UTM~-X-wd{gQN`8bq^U&DHH32KISpqSnlXEJBd` zb`Ej-quPO1tDt_K!Ezn~0s47|a~pgs*@|?qS@NIq$}=s>dt?MeCi&Up7S6eyfB8A} z%O8RM@(W#_S#VPmwGQ>tIN^(tRyG9TM^chGPj<(Rd%=ZAh1OgjeybdW!hVKbTKCW{Ng%9Tdt)=IeGBrfbvJ>OGY~$Vl*%Wx;AOW&_;rlMx}pBT zHyu~(2L5-0l4&*qrr0bIl~RSDQ9!< z+4qgE1Wu>hCfA$LWXP8`)MsB$9BEV$U#Ar-OSJ zbi;41j(bg_5uzF8P~Z@95upeCon9MG0ADQ^ylG zi@DoR82-*U-H@$eJE5haU(}P*KKp}vLe$gCF+WSyo=)HLVPZ0* z)|Z<$bY#ozhrmM0=l6K_stp50M)dSUuQM*gFKK~S7-vM;jZ7hgrT$ z-9?Z+M*k5kVtXm;N^Y^nI8lccwej7xbFL;dW0@C1G)@qc4-iB=pJ^D=V;bE|{ez@T zb-%I?FO1P2-@V8%wC3f8M_$?v~ zXMZW?!4m=Uz%Er60cT5fJXQG8g{nN_#XPF;*NZ7y_L~pLz#Q*LG;mMhuSv*<)5Zf{ zlj5k7@(09RHb+bX0uHHfey{TQpgTF1cD&bleZ&>RG1k#OGvyAPh`tlv$O}J9rOwoo zA*UnU(~qCmJ^jsPgB`_>Pk<^x9hCC9xO0Jmh4}0qhe!+Gs-Ht5X>shD$v%&mcxlaYFqnA8~?+vbbiiT{EY=DnUF^Qwx#FG`$a@;6Bwu|Y*{|4JuQ_^pCgkGcMg`De~Eir4>^y&qTL)(Jn4Dykoa(!6Wr3ro^W z!D=Tgky$3!QVUZI&N>)*st-PP|?3G82!2#hgu-KW6C{*Wb&EOyI>0y~;`b-1cT> zlp;jQF4-w&ZVG|h7+vmH3n|0YG+_tJ+^O-)c zt?@70u^(Aj>^OcpAIwuV-maoGY-&whqKQtdUrY~~nRx3#1Wk_V%`oS5LQezUE1Iph zzrpt2ysJ_TCHhLeUeeT{I>T2C)~Z9^u?N;y0#6wF$0h9q6x>|TjZg3_<2N?q@L5t! zS-+OPCW#Q!`+=OZ6Miz_E*K=GW zTOANxfcsj^0<4305?F{(yc63y(uL9~?%uZ-;NR4M+%g6(uFF>rczC#>eZ0CvN}71D z3ty~A@5jMRAoF!MsJ-^$J?ryAA2~JX8c}FoFODZwX8~DP# z#Q8pj5sEgt_$jlIgz;N7uN)e)6W)bIO=uK*nuYVhKm6Gj$C7vz zemLgs*LxjH7!6W2Pl-pinak^%TRa%pL3JrWa8fPpeIGfU)P7PN$XK|s5_dN?UgYs% zA@*a7kc~W@4uccso~4ePvx|%Rde*avAHtP7iU1?G^w)f1AF)uAVSUE(0-!jRx_U&P zj9MkW*ujU>8g`aXTbzrK$9XeZCNEYl1}XI~07GaLr@W~X`-b3K&IIU-Ta5f-M5Nguv@XNF zuQm1RgWoa8hAGs_N1L8yHm3O+!IBr(6HgO%f_5G6N;1z@!E4rUXp3 z0ipd_RKDb2mKB`4X%}Mj#`K(c$>{onEsFt7l|aPq+@4-t@BwD^$o{;S}2 zF{_-mL8S*a?^Sa_qWb!t5(ve7jMIP(Lj58-!_a-m$3QZ)K(3rZ=i*Xjc%b9>Rp}FG zjq`|E_Jrp%*aUd9Apm1Y99;nxb&Lqvmyp~c zVH3+U5yr@@dt=6-#m8tAeH=D09Y4KZ%%WW3|MbDw#cBr@mF@F;i-{fVyNUm><=EscX^ihYrj^t^WmhhOkw z+^;r*e!&ga5%NaxoD)DLYA$vCCA$zM16&|CIJl54%uS3pc<-)o)#D710o%x|HMTqW zbL!Z18$weLc%D$kZdJNkjZtuGZ5jVeYlr`$KyFX=xkh)~Pe125TcMJ=qsWKivH?h= zA}ecOefRk0O}M`l+;v|2E@x&H*T_>po#n-}V%)Wa{{~eI|EXOw?P&|DIJUSgp2Jnm z{fBq>@#){ha5Tb_-G(3oAS|TV4rxqMsy(1+<(w#ELXx0?#ws1 z;t%k%P>;N-b#OWvxXgET=iFe0$5r5v*c6t-amSyHScJ^^0`+Lz7xsxXex5l!ZB<6k z>ZMW#Zr)4lTc!cVEt#|m9G!(Z1^ZkLc-)>z`m)gMPQyzz%e_Z7Q%gp>eflPz>F1&5{Kmn~{A}=!kH%Dtd>o$jbr8a^LGbSbAfYk$=(%-!Kft=mq;0jLOX7HZZ z8|xO|+6iPbH+Mt($^jggKBJWn%&QW>Ind`JnMaYKFnkx6OtPPFzq^6dfvJ;#VjbE( zgj7eam-YB;VKq|Wlv6A^vL{rxj6-u%J!h|(+LN0qpA~2PQ$UJoF$X+{d%Rn%LC zK^pda5?On<2+SdN_n7lP-sl5?(1G!YtjT$I=nN*I}W}Gv?pM9 zapuvwK~lhX{OM)6f7RZ|95#xv-`Rk5hVely{rDDTfU-)hO24?(VD2Um{nVsbIVr%z zDtL#;%M4G)|Im7dm*$rk3EGF}Apo8*lEhH7hD^<^{E&|}>^xl``+~oVy_rcV8*=Fw zN)KFV*znTAtVzs_V4C4DGNZmK4Va;Zn8eQjR2d}IvOTtpXzY9vI^=BE=-FfBbByn9q+WNY&>?7 zR(y87BV3Er(lZ*)`^%*K#O4xrb6x}@rLf~LuovvAPtuPL9w1H!{9S|QzQ3CsG>vbo zxV1rM12*tXd*?AQ!#+iYXfru*f9a-g8gOav^S{;mEr0|mH2Vf$6`q%eNC!A14L3=) z7ccX9;TRPkvSbCG9?B+MRd_85q9Yxwu3_Mh;auMQ0}gdy#OoH(RaR@nI+V^1+;6j+ zYcpWRhh|{S7AC}f=~e2tHEdzxRTX}(sKr+})Br+fm}!GoFG1k>hc7Ump=}YehOW6+X)QsyVlQkapfw ztb56^{|-mZPB_HL@gUvq>w&XriJyElVZdM;A>Xk!U{xgH!g)zxWFYS3rT{xCY7J)2 zs~|3cBGS^Gw4;pQ+6aeClDoQ-NHTpd?;1cLC;XVv8Tou6%y1muJ_xP**yl>Yt0pao z0!N^5ADn+G9cDaJH!q53n^q@Rr3o(Pa%`S?m0t8S0!>Wbl!=i z5<|&|C$!l$tcPUkOvOmSbm9O5wnRzGp1-fMgw&h9@dGr3ZnbW!NGAfNNz-!-+19@H zDg_~Nlj9nh$4lhChM$vl=GK1LQ_Y$+q9ftoxjQ>1k9~v-%wusClm{Yhfud6kw#KR( z>75BTaMHopPoE~IE!;P;F_J(ILG?LY61@Y|%8b&UbI)rYMH6K04*-q7W z9b>f|iv&u5Jm!_lpc;q>#Dt;Nx zPs;Ym4F@$uZHvgs9oXw=&WrF7ZCR}+)_%TTOW-UkNQ=T_=@!T0N}s%itm;X^JhnpH zvDNQKbM$;1iC0z6XKnh8(?ATFK_hQ#&dMg;RzMWNk`5XH3A!9d@}$7#yPf(ggmeO^ zamZvnaNs*#y`q_A%%inRM6~*xi~x;zFk^Eg_?;vgo8l5vLZ)@B(G_o;v%NVldLx1}8&1v|3KPl@vzBQi|fM4Kl zC2L$dOI(FpO1LyDV(Fw1MNWQ)%RX9sz+kp7sb*yjJ1H{!jd@vCHYQfTQZ|O%jWp$4 z(DAYRB70XaAdN#>ygN!cAs)VHnLr(%F&0g41833BF^fqGO-$f9dG$tmqlrTiiC;$o zgx5c{#7T;$^?%`?X>(5enQo}94iog-kV`?4NYgf`qKE?6P23^o&!|PU)$W3BBn~hL zZu*Y();|Vuo#9wQkn99niza8qEyo?^4B8)^Z_J{wMH_plZRyTr_R?Z7b$fd!Y)RXBXDxkksYy*wwxBLP=T~Qtd8mG`=jD+3%_s)mg6We%*`L0b zf9TI_!Vd>rj<&6gUJc314D&hj6+4BWo<`9g<=&xeU+bFcTm+@wHMMIwnY^w!X^3&X zg2!tu(E?h2;(s#tz$XFQDJQP>zl`ItGw$phNv^4$(J#KQ1x|JtQlO*zb+Jb90f_W9 z6ZBbdzt7##q>|41da0c`QS91?c1iR@gO2h@a_24g#}Yoywz-a%eJH-}*&Y2Jl|RQH zxs%*WC9S}lkdBkc4PH&^C`~M){9WU(>oHtmEx+(J8eBr|oSfQ80V*8a&Mr&EywX$s z(XGw6tS{+B@*x$WxO@GPHKCREEgW=K2D@Cb%j6KLZT;LG%|?Tz!o{j7U#XQXyT3M} zRNUp_qi~;Hf_A}uZX{1$bcALUgIS+wW{%dc@OwG4}TL?1xbzIFYI;OBp`&sUZpM*C|bY_wq9BO1g#`G zyhf|oQR84|qTm(r<<}Co>u5I3QiVr9f2ymS+%AD8tHxsZ0|ElD)L-^1%k!rFS3X47 z^{sONE1ovw(csoPUFLjI2kof;Al{lD(!G?UwsgI;h)Kv;N%{D)Y4}uHCnP)#<7pdn zl%mhWIj37}keRBY)JFrxch!A$B@G(jFHDUHPjnHSF)tpQi@0+6-8sdM?P7?PluDAn zw+hLd@yG8wVXC2otM9U4t%58QnaT`6KW_p36jlYT7Wr(~qaJGovT-HsPqRsAJtWO& z5xcrrAv}!KG^;2Pws(Oj`Y4rD^pf*1SsH5S-`0N8S%+%=ANrH8*Dvz`?7iTOBBQg; z#)7jtNa+P)#T*!H-;c<H{a|^_Tr>kAJdr0nj)_-mdIn)2lrRw2 z9hI~=UD!+rz;^1pW9lLyaQF%OWSucD0fm6C1-1w1t}`45Yvd<^1b5on5LnrK!rarO#mT-; zlaw}oc2xWgH_>Qq>>^dzNj0(NyS%yI89KWB4>`w8JTP{Sz$)vXu^<~IB(-dR!c0c@ z=qDlX`*FSOj-q@r*xd3i)!R{-0?7UC8x&?Hu5&{*d5(q=BN`f*C)(ei?d*wl8Xnv( zFOuwoFF$OCj-^cgpg1m#j0KB>vfm2!*dQMFm~+VrU}FfvL?^wmEt0i6a_}4TwJy#k zo%9h-oq&N>!@_XXRpq`U##>$5b9s)J8+}d#BCH?-U+N`G6#}E+c9*DBYG2^i9Y780 zHU?|y>2WF*ru7?>Ya=qD?E2!e`tga)8)|$ZEdece@OfXGn1j+{&U zFl+<+0Fjw2%lJMjWdJc1JqhNL3tDGHIW|0nR(Qz8orO?+0LD|>Wjyjix8U91K9CFW zft@N>BkO8II|4>s0jr-S-kNV1e6#weaqcge-D8a5*j(E!Z3aEwcPOZPP^2rcbe1Ky<{q3 zs+MG_F8)m;w}lvvO9G*Vf|ZqsM99t2fjtL+lf~?6CGr}emFfVkRJx4gUqkZj>vKAz z+O146A=7hxNuV;AP)|0@_w%~F+Z6@4MAzEP>Zp7%zWq8t7N)+$c?`yhvp;Ip)k=j! zL?ADZ*~-!FyU$Gu_557>KMrJC!Sp&C;(jnzn~#Lni)s>2Dh14io6_NlPTF290vPH+ z^se_WbGssZ#^5ScW=IK^=1tOfY&A=_eG(`lny1%iROTSd0dZmZDj3HrCNMCEM5eP% zX8_8i-@_>VeNEOOV4yy1*Y4Q0#Q}5sXm4)qqbfljk8$7mD_@8I_T*0ICyMk5i`r8m z>o&2} zrgodm4S1mno%s)KE~4DCk0?F+8r^AI>92I^+N%y!W?%kNNb~lBF_Py99i0)#7)?*N zb&2l3Tm^)^u{)dW(W9Y{3G6TFB4sCI8QvA0r?)ID_$`3t$hgJ z?{@Y6l9jGtaxNo()r$@jOWldZOd^qprjXbXwqBWw^Tx3TW%7~gPafX0f+>r1atVtY zDk;~K0oR_?vjbAMqHN+x1P$yDZ?w=sx}bY}K-}^zSujq=<1ylou5r4$=8+yA{v@!e z(9n`{1C4$vWHg*BOVQY{+36)r)`Wl~4lRchSvfhdYK;a(?oS*pY+7!)I7n8+pJWV} z=yCbhnJ1+h9c_Bx(#UlWQ#fCt>wBxrnKepO?}a~lVtOyu=pUxPx|TB3mqERv+>vFeC0gx7J!4(yEstl z#_x-Mx{qCevl}#M{NM$qrHub#2LAfvW ztNLGK+fr3jVxns$(Y~X1$QoWKf6^oOwFp1Bi{YQ)_k1zXiSUQmu5K4j_vAHU{feR@ zy7jJh-Gij&-_a?k?8M*gF4Pz1@DU8LWlGDTR#Cs;4bf;|PGVN%q5EDKIw-V;Orrak zXOnFSf}})d!bwX8WuAO>BiuSRHj2t;t_j+ap8ykSR{}^2!`2Gq+O6e~cOe&4d;?vNlG4BWmJdV}B=4a!4 z1WZk{?s<@#Hn{EkslU9MY?+ql(au>Yb3pIAdPNMmGxJ;Xp#4#BsFm*0nk0I2qlGow zN-GA#fAK32wK`V|rfDmaT%}5`Ay00|1fzn@qu4_cJKm`ra<3A*(eyWP8@0ma9wH&~ zJHl~imxzYIES{qFtjcSdd-vTX>cIr}#m0?YB;# z4T!yp*Aqbn1-Bi)gJ{O;7{MS_yH3aS5ll=P*4&h57|~c%nNS_s{$A2b*JXHXdo80W zeJDXQCHGh9Cz173cU23rYp%~aG%PXc#{<393M4kEda`0=vi9EK*L6?j(lmSzFF#rj z=6jKj&QA2O%~u5zxhmE-hc~ryfmMqOv(wX5IEAJau|<|QVPRXTI#%Q7O16S zSG8B`hf~oR9CAaZx~)T}6qH{9f@b!*`{OK*H=bq?Nbb^|QZJQ+nl3ymc-up&t=IB61FQF1!7AIQJ5ZhVs#`^*pkE_7w@2Ao0b$!O8?gEHQLrXMV{b8s}3Qz z7amb&eBP)92-MY?QJ5F;E-s0Kl>!R+X(S9~ICFaGD}skHewch-feJ$+0X?h;=)`@! z)PHA|NJr<`ylt^cD@#YJ#`f`PMBB4(@XsXx@2AS$TzuoD`B9 zqXzhXK{RWugH|I!wY>7fHR%uMcpTJ0v8Z@?6IefQp$sE>xqD@oSM(0&2+GbCbk?`p zE&|>NNQChNYvZ^cy^+jbiS z;EisX2;?vJ4XDaYPBk_fA(VUd@&|xdQ@7=_(Mvzd9Qj;*JA-@iodi7%uq31WA@rt; zz+)UTDc7TLQ(&ZjxV)rvShIB)G+fe00)dhl;sg8oeCWDg)z?^v2n{!`rez9O5`&${ zi}QHeGF2ukX`X1OmtCD?z4^dBK!P;fIyqZt?c(F?Wb0cM1E6&4+<)Lezvf{|YB4uG z#|>JKHkMumI3cGku9~guqKSz0lQOu(L#RZA#?Fz@ueA} z!V+EPYva_q$>lrl4|LYneECS$iX=OCM*7{c_GekklP+;xu!?eroSm;|oXZi9eXKult(ci^=632#@Si1}R>~zm1 zuX*-$04TH4{*5)d_lEjgbabbDv~Jxnq?>QqgPf@fTw?R>IW3X~JQDL=M>t6t(cBF6 zEp7FNN_SRh+uC?Tl?*!G#0{5s#F=7V0z;N*V5&W_T_QGA9yzyZ*;J)RQ>moLnLs9;prh;l*X$Ytv#a29F)Sq|y_`mUZ{?#LAT%6MdJtWafKVM8 zdJ`Wt9geeI;>Sg|-U0*CSh@%iV&)D>uds!4n8(xg+xjZ5ThT5`^QD+>tt3BL%WF&f zGrzfAvPFY~9mEXEDTp2{Hzk|25?4KKgq|ss<@J;CF3rpFmCl!nCkyfnbr9#7qomPF z%BSe)zM1}qCzt9Q@_?spJ#mA|bQxQ=R1H&wc`2UmR5P@YV?~BEw(Sgp&m2MBlo#OU z@GY(u_Bnf1+z^rA(b7gSb8Y%DR5x7^L);LgFr!^(>!9LZz>NI@vrME@7kH&Tm+v&H z`twmK%qZ_wZzU<2tybqtEX`JKCHrR|7Or z@A>)$1Ar)-c@z?-;G31GrTS>r5tYJ~B6*+@21N-yw#vs6$=X;T6Xz=JJ14?lmm!@l z-qo)PDZAF&(W#tRqskCZr}$Z4>wlW?{+Y&?uZj|dkPFh{=uVo9HMqFLBPoNHZ;pgEK4CDOb%-Vi`sPXP;@#}T1(mD{&%)YWsB zCsf;}ZIg9YhKdjos*6Nx|41O0o+lY%Yo+zc5dnOfF6YGa->RH$IsZd)QzI5(dhV?5 z)KshiEujYo8^8Y)=lev5rKuB3RmFFK)xCbWnfD44a3vR{Pt zaEze$+&9BByP7%)%v>|~)v)6#TtY|QC6(Oo*hfa}L^-4NtjQ_NN5IHms_)LJM7?hm zKDngx33jQjsYri|IyI<3fqVHX($V$a`B%q)6eS_ENQ%1MPAp$B=I~#%d%aYFu&C_D zW4#T56j!NqU%5btcx_+dnx?wTFc$e(C~tWs0hz=U)FmU0Bum00OUA~a)C75{HG;9e z2pi6W;P4s&jH;wSQ`5Yhmq;fdU%z?!zG(w!tG(UY+Eyx8^nSu7zcd40(d`OpSI(*%7WAK{$s{D}yseC#Vs4unj^q>GnH@nv7A64a4&IfV_nV+yMu09B5Qh1_ zZ{Xt8-dNCi*ra))ED7|`MIofA2!Sw`qN)N7q!aZ;999>LS|>F*{TzKT=trKTUT!%Sy+_Hma_Ukz3Jokor!z;*jt{ zZ>*Xz{KVr4VT(j?ASG;a98eg?t_vB80GS1?ER@@Z?pLj^Q|>Vv3!sNRS*#;lO;Bb= z*_&u3n0`Ni@0w44vqeuR(&Yyw=;8n9m`AY1+${>-2^wo|}Sv}$m; zLmO{Pb23#DFTrN8umtiMH!2leLV3@tyHn$P@d>kg`R~a4E${4cg{<{x{jFsO_w7R$ zSm><2>1#>c*PZC73;l%SGe>G`SOJ?5uB15{_gKt!0uh7lr~af`AWaFim0Hz3Q42Vs za_JDiXjX8tPHQvPGe z6iOY`dH8*j5(^&Vp>#h_TG*1?Tz&w#@9hWtW~rIFA>u$$r0>SVpHN!uwA@=PcBA!B zRsC{YCb&r}rfF(&IZxQ1QoveCovY0R%R^G3QwVE+f6#Mq#@vmcGWp{8fyAssBU(1o zIL~qY)v=Jt<`I~$8bDK5{s8UUaSA=+P%w6i1lBuP^|+-?KHJea&wab%8$Y({y2#Ce zsHab@moQLnMe+v%SROHN+;e*&e@=x(>WRyhknbz3;9*_b4858lof%pmcz}V{#6n!C zIr8^Z!illWH_>G<{nE0+LPhG`qer7|YVf?!)hU49$0S%3N0pN{u|IC1g#g8Yd6u)k zW(VjrU!EUet<^EoH~xseMPe-!zN0bkTZUtq|2=oRn5r3dJyEon<~oL$EZVVhUwH(4 z%c%XmbpBWglpB7$_Lsdk|E}?}Tj}6ub?|s$6qGvGe-g|OvDhYTQibqBf5Lc?RX}kUemeYpmVeZnh-~dy!!Pps zW?xYKR^)AYUY5&jg>U%7vslj{YI<8H>%CX8CTFrS(Q8G{yAWRo|5weQ--&R7`A&u6 z1F2UAkXhk?ncQPaD*d_+2>bN)KrDeJ;;=5B+s@@te|{#ZqNI+sz8>e{sVF+5(zqQi zZ}1_}qJTvAF%#pOftzNf&8eaWjayN#5;#hglj;|AQA6RiEhF!+no>vy1=vc)p2H-uE$Q22-&6g-9_dRD0NVKjSs?sfJ3N3qYDK&8BFXPcS9P^6V?=6(5$Jm^ zu{U=9>pfhB1<8VFxH#YXD~Y>ADL0Q)WqeqdZrRX}AKI7}mQ3;D(^?m`e58O4z7LMs z0KWRwf96|~r*BaPwq4=B6$dd^p=<;2w;N!`Sis?MUl%ZXo?LkX7ziLGcj!OusVB}( zqZ>?$;d^X^Z14J$(%2`bAaul^?++5n&Ao~sFIb}+_I~#u_)jG8%O^xbV*m3=C;mFf zy$c@+e{Z$-|LX&P6x;sig9`tOj{OVHLVp=3=w8P?9?i|^NN~h%<8ma9{T6%w&wsl2 ziT*$M+y6XWKJrgj_Al5e{nc!H7k+vDPi=<|_FAm%dyi54g})8_U*9FD;M1=^gJ~!9 zzk93wrv1MervG&-_P>wrf4{H)UmI|JhK;9W|4Y0@{(qY>#~NDoG>{7gURAgof8xFU z+y0$rUg6QInUXk8@Ap9wE^o`u8dVPza);9k?o}&a~cI6 z0KaF+Oc&Js2jjqBRw@1hQniHPOmM`C@b0o2y1Q4mOWVQG6-DL@dns4SU>mhVYuhp2 zHIPx!fAzilRb+c)IkC29t$k2eP)KNJHW>ma!bAJgLeNRvIPZM}72d#PYL%$2{ustOR*@knnQ#1qfL z^Xoe-=5X_nMSfG$c&p^fwMPFrT#@SLR`3`5uZN^ppdXTwT8TvHo+$_2`wQt&(eO8K zCPx|CY)UQK)?YOtd1fMVb1x@E_mv@eCLB#o6LkW(TQRxCf$*7S5b&C!ZjLMw&+ayO z{;v}Z%9gouB{I=lY06z8&p6x5cRx;%qx;)dJ?lr0KI8cI`kC_->goHt$NN7<@jy=b z-&g+6S@Qn3{?F!>Bgd+!{QK4f{{K_0P+VNKkdhm~3-5pP|2`XhV+2->_y0)m$luZ1 xyYN4=)&A%I=RWTLp6*{vyLaXP{2)_zP-aXWE=9aRd_YI1bsKyuOYOn4{|hIyqB{Tp literal 0 HcmV?d00001 diff --git a/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm b/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm new file mode 100644 index 000000000..ff5184aa7 --- /dev/null +++ b/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm @@ -0,0 +1,15586 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm b/common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm index f28997118..6643880a5 100644 --- a/common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm +++ b/common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm @@ -1,342 +1,342 @@ - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - + + - - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + diff --git a/common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm b/common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm index 669f1c0f8..56aa7b9bc 100644 --- a/common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm +++ b/common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm @@ -1,1654 +1,1654 @@ - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - - - - - - - - + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - + + + - - - + + + - - - + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - - - + + + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - - + + + + - - - - + + + + - - - + + + - - - + + + @@ -1656,9 +1656,9 @@ - - - + + + @@ -1666,37 +1666,37 @@ - - - + + + - - - + + + - - - - + + + + - - - + + + @@ -1704,9 +1704,9 @@ - - - + + + @@ -1714,9 +1714,9 @@ - - - + + + @@ -1724,9 +1724,9 @@ - - - + + + @@ -1734,19 +1734,19 @@ - - + + - - - + + + - - + + diff --git a/common/autoware_lanelet2_utility/scripts/lanelet_id_aligner.py b/common/autoware_lanelet2_utility/scripts/lanelet_id_aligner.py index aa01ad8c2..ca19aaacb 100755 --- a/common/autoware_lanelet2_utility/scripts/lanelet_id_aligner.py +++ b/common/autoware_lanelet2_utility/scripts/lanelet_id_aligner.py @@ -23,7 +23,7 @@ def renumber_osm_ids(input_file): root = tree.getroot() id_map = {} - new_id = 0 + new_id = 1 # Collect nodes, ways, and relations with new ids for element in root.findall("node") + root.findall("way") + root.findall("relation"): diff --git a/common/autoware_lanelet2_utility/test/kind.cpp b/common/autoware_lanelet2_utility/test/kind.cpp index d4787b8bd..d2fad85ca 100644 --- a/common/autoware_lanelet2_utility/test/kind.cpp +++ b/common/autoware_lanelet2_utility/test/kind.cpp @@ -44,20 +44,20 @@ class TestWithRoadShoulderHighwayMap : public ::testing::Test TEST_F(TestWithRoadShoulderHighwayMap, LoadCheck) { - const auto point8 = lanelet_map_ptr_->pointLayer.get(8); + const auto point8 = lanelet_map_ptr_->pointLayer.get(1); EXPECT_EQ(point8.x(), 0.0); EXPECT_EQ(point8.y(), 0.0); - const auto point10 = lanelet_map_ptr_->pointLayer.get(10); + const auto point10 = lanelet_map_ptr_->pointLayer.get(2); EXPECT_EQ(point10.x(), 4.0); EXPECT_EQ(point10.y(), 0.0); - const auto point15 = lanelet_map_ptr_->pointLayer.get(15); + const auto point15 = lanelet_map_ptr_->pointLayer.get(3); EXPECT_EQ(point15.x(), 8.0); EXPECT_EQ(point15.y(), 0.0); } TEST_F(TestWithRoadShoulderHighwayMap, is_road_lane) { - const auto ll = lanelet_map_ptr_->laneletLayer.get(1275); + const auto ll = lanelet_map_ptr_->laneletLayer.get(47); EXPECT_EQ(autoware::lanelet2_utility::is_road_lane(ll), true); EXPECT_EQ(autoware::lanelet2_utility::is_shoulder_lane(ll), false); EXPECT_EQ(autoware::lanelet2_utility::is_bicycle_lane(ll), false); @@ -65,7 +65,7 @@ TEST_F(TestWithRoadShoulderHighwayMap, is_road_lane) TEST_F(TestWithRoadShoulderHighwayMap, is_shoulder_lane) { - const auto ll = lanelet_map_ptr_->laneletLayer.get(67); + const auto ll = lanelet_map_ptr_->laneletLayer.get(44); EXPECT_EQ(autoware::lanelet2_utility::is_road_lane(ll), false); EXPECT_EQ(autoware::lanelet2_utility::is_shoulder_lane(ll), true); EXPECT_EQ(autoware::lanelet2_utility::is_bicycle_lane(ll), false); From 4c2da1d8ccd60ad3ecc7234c7b9cf3ff7329a89e Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 5 Mar 2025 16:00:34 +0900 Subject: [PATCH 07/17] adding test for left_lanelet Signed-off-by: Mamoru Sobue --- common/autoware_lanelet2_utility/README.md | 39 ++++----- .../autoware_lanelet2_utility/topology.hpp | 11 +++ .../src/topology.cpp | 8 ++ .../test/topology.cpp | 85 +++++++++++++++++++ 4 files changed, 124 insertions(+), 19 deletions(-) create mode 100644 common/autoware_lanelet2_utility/test/topology.cpp diff --git a/common/autoware_lanelet2_utility/README.md b/common/autoware_lanelet2_utility/README.md index fa1c5d642..a84d0b069 100644 --- a/common/autoware_lanelet2_utility/README.md +++ b/common/autoware_lanelet2_utility/README.md @@ -26,25 +26,26 @@ This package aims to strictly define the meaning of several words to clarify the ## API description -| Header | function | description | average computational complexity | illustration | -| ------------------------------------------ | ----------------------------- | ------------------------------------------------------------------------------------------------------ | ---------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `` | `is_road_lane` | | $O(1)$ | | -| | `is_shoulder_lane` | | $O(1)$ | | -| | `is_bicycle_lane` | | $O(1)$ | | -| `` | `left_lanelet` | This function ignores the permission of lane change. Also it ignores `shoulder` and `bicycle` Lanelet. | $O(1)$ | In the first map, the green Lanelet is the `left_lanelet` of the orange Lanelet.
In the second and third map, the `left_lanelet` of the orange Lanelet is `null`.
![left_lanelet](./media/api/left_lanelet.drawio.svg) | -| | `right_lanelet` | same as above `left_lanelet` | $O(1)$ | | -| | `left_similar_lanelet`(TODO) | same as above `left_lanelet` | $O(1)$ | | -| | `right_similar_lanelet`(TODO) | same as above `left_lanelet` | $O(1)$ | | -| | `left_opposite_lanelet` | same as below `right_opposite_lanelet` | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | | -| | `right_opposite_lanelet` | | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | In the first and second map, the green Lanelet is the `right_opposite_lanelet` of the orange Lanelet.
In the third map, the `right_opposite_lanelet` of the orange Lanelet is `null`.
![right_opposite_lanelet](./media/api/right_opposite_lanelet.drawio.svg) | -| | `leftmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first and second map, the green Lanelet is the `leftmost_lanelet` of the orange Lanelet.
In the third map, the `leftmost_lanelet` of the orange Lanelet is `null`.
![leftmost_lanelet](./media/api/leftmost_lanelet.drawio.svg) | -| | `rightmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelet is the `rightmost_lanelet` of the orange Lanelet.
In the second and third map, the `rightmost_lanelet` of the orange Lanelet is `null`.
![rightmost_lanelet](./media/api/rightmost_lanelet.drawio.svg) | -| | `left_lanelets` | The input Lanelet is not included in the output. | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelete are the `left_lanelets` of the orange Lanelet.
In the second and third map, `left_lanelets` of the orange Lanelet is empty.
![left_lanelets](./media/api/left_lanelets.drawio.svg) | -| | `right_lanelets` | same as above `left_lanelets`. | $O(W)$ where $W$ is the size of the `bundle.` | In the first map, the green Lanelets are the `right_lanelets` of the orange Lanelet.
In the second and third map, `right_lanelets` of the orange Lanelet is empty.
![right_lanelets](./media/api/right_lanelets.drawio.svg) | -| | `following_lanelets` | | $O(E)$ where $E$ is the number of Lanelets to which the input is connected to. | | -| | `previous_lanelets` | | $O(E)$ where $E$ is the number of Lanelets from which the input is connected from. | | -| | `sibling_lanelets` | | $O(E)$ where $E$ is the number of sibling Lanelets | | -| | `from_ids` | | $O(n)$ | | +| Header | function | description | average computational complexity | illustration | +| ------------------------------------------ | ----------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `` | `is_road_lane` | | $O(1)$ | | +| | `is_shoulder_lane` | | $O(1)$ | | +| | `is_bicycle_lane` | | $O(1)$ | | +| `` | `instantiate_routing_graph` | This function creates a `RoutingGraph` object only from "road" lanes, which means "road_shoulder" and "bicycle_lane" Lanelets are inaccessible from left/right adjacency. | | | +| | `left_lanelet` | This function ignores the permission of lane change. Also it ignores `shoulder` and `bicycle` Lanelet. | $O(1)$ | In the first map, the green Lanelet is the `left_lanelet` of the orange Lanelet.
In the second and third map, the `left_lanelet` of the orange Lanelet is `null`.
![left_lanelet](./media/api/left_lanelet.drawio.svg) | +| | `right_lanelet` | same as above `left_lanelet` | $O(1)$ | | +| | `left_similar_lanelet`(TODO) | same as above `left_lanelet` | $O(1)$ | | +| | `right_similar_lanelet`(TODO) | same as above `left_lanelet` | $O(1)$ | | +| | `left_opposite_lanelet` | same as below `right_opposite_lanelet` | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | | +| | `right_opposite_lanelet` | | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | In the first and second map, the green Lanelet is the `right_opposite_lanelet` of the orange Lanelet.
In the third map, the `right_opposite_lanelet` of the orange Lanelet is `null`.
![right_opposite_lanelet](./media/api/right_opposite_lanelet.drawio.svg) | +| | `leftmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first and second map, the green Lanelet is the `leftmost_lanelet` of the orange Lanelet.
In the third map, the `leftmost_lanelet` of the orange Lanelet is `null`.
![leftmost_lanelet](./media/api/leftmost_lanelet.drawio.svg) | +| | `rightmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelet is the `rightmost_lanelet` of the orange Lanelet.
In the second and third map, the `rightmost_lanelet` of the orange Lanelet is `null`.
![rightmost_lanelet](./media/api/rightmost_lanelet.drawio.svg) | +| | `left_lanelets` | The input Lanelet is not included in the output. | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelete are the `left_lanelets` of the orange Lanelet.
In the second and third map, `left_lanelets` of the orange Lanelet is empty.
![left_lanelets](./media/api/left_lanelets.drawio.svg) | +| | `right_lanelets` | same as above `left_lanelets`. | $O(W)$ where $W$ is the size of the `bundle.` | In the first map, the green Lanelets are the `right_lanelets` of the orange Lanelet.
In the second and third map, `right_lanelets` of the orange Lanelet is empty.
![right_lanelets](./media/api/right_lanelets.drawio.svg) | +| | `following_lanelets` | | $O(E)$ where $E$ is the number of Lanelets to which the input is connected to. | | +| | `previous_lanelets` | | $O(E)$ where $E$ is the number of Lanelets from which the input is connected from. | | +| | `sibling_lanelets` | | $O(E)$ where $E$ is the number of sibling Lanelets | | +| | `from_ids` | | $O(n)$ | | ### complexity of `findUsage` diff --git a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp index 24ac75ca5..1389437ea 100644 --- a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp +++ b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp @@ -17,12 +17,23 @@ #include #include +#include #include #include namespace autoware::lanelet2_utility { +/** + * @brief instantiate RoutingGraph from given LaneletMap only from "road" lanes + * @param location [in, opt, lanelet::Locations::Germany] location value + * @param particiapnt [in, opt, lanelet::Participants::Vehicle] participant value + * @return RoutingGraph object without road_shoulder and bicycle_lane + */ +lanelet::routing::RoutingGraphConstPtr instantiate_routing_graph( + lanelet::LaneletMapConstPtr lanelet_map, const char * location = lanelet::Locations::Germany, + const char * participant = lanelet::Participants::Vehicle); + /** * @brief get the left adjacent and same_direction lanelet on the routing graph if exists regardless * of lane change permission diff --git a/common/autoware_lanelet2_utility/src/topology.cpp b/common/autoware_lanelet2_utility/src/topology.cpp index 96d8c8b72..c3fa17e2d 100644 --- a/common/autoware_lanelet2_utility/src/topology.cpp +++ b/common/autoware_lanelet2_utility/src/topology.cpp @@ -25,6 +25,14 @@ namespace autoware::lanelet2_utility static constexpr size_t k_normal_bundle_max_size = 10; +lanelet::routing::RoutingGraphConstPtr instantiate_routing_graph( + lanelet::LaneletMapConstPtr lanelet_map, const char * location, const char * participant) +{ + const auto traffic_rules = + lanelet::traffic_rules::TrafficRulesFactory::create(location, participant); + return lanelet::routing::RoutingGraph::build(*lanelet_map, *traffic_rules); +} + std::optional left_lanelet( const lanelet::ConstLanelet & lanelet, const lanelet::routing::RoutingGraphConstPtr routing_graph) { diff --git a/common/autoware_lanelet2_utility/test/topology.cpp b/common/autoware_lanelet2_utility/test/topology.cpp new file mode 100644 index 000000000..e95ac05d9 --- /dev/null +++ b/common/autoware_lanelet2_utility/test/topology.cpp @@ -0,0 +1,85 @@ +// Copyright 2025 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 "local_projector.hpp" + +#include +#include +#include + +#include +#include + +#include +#include + +namespace fs = std::filesystem; + +namespace autoware +{ + +class TestWithIntersectionCrossingMap : public ::testing::Test +{ +protected: + lanelet::LaneletMapConstPtr lanelet_map_ptr_{nullptr}; + lanelet::routing::RoutingGraphConstPtr routing_graph_ptr_{nullptr}; + + void SetUp() override + { + const auto sample_map_dir = + fs::path(ament_index_cpp::get_package_share_directory("autoware_lanelet2_utility")) / + "sample_map"; + const auto intersection_crossing_map_path = sample_map_dir / "intersection" / "crossing.osm"; + + lanelet_map_ptr_ = load_local_coordinate_map(intersection_crossing_map_path.string()); + routing_graph_ptr_ = lanelet2_utility::instantiate_routing_graph(lanelet_map_ptr_); + } +}; + +TEST_F(TestWithIntersectionCrossingMap, LoadCheck) +{ + const auto point1867 = lanelet_map_ptr_->pointLayer.get(1867); + EXPECT_EQ(point1867.x(), 0.0); + EXPECT_EQ(point1867.y(), 0.0); +} + +TEST_F(TestWithIntersectionCrossingMap, shoulder_lane_is_inaccesible_on_routing_graph) +{ + const auto left = + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2395), routing_graph_ptr_); + EXPECT_EQ(left.has_value(), false); +} + +TEST_F(TestWithIntersectionCrossingMap, bicycle_lane_is_inaccesible_on_routing_graph) +{ + const auto left = + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2447), routing_graph_ptr_); + EXPECT_EQ(left.has_value(), false); +} + +TEST_F(TestWithIntersectionCrossingMap, left_lanelet_without_lc_permission) +{ + const auto left = + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2398), routing_graph_ptr_); + EXPECT_EQ(left.value().id(), 2397); +} + +TEST_F(TestWithIntersectionCrossingMap, left_lanelet_with_lc_permission) +{ + const auto left = + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2396), routing_graph_ptr_); + EXPECT_EQ(left.value().id(), 2395); +} + +} // namespace autoware From 33b61d69d98991d7a021ae38b69e628f306a54e5 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 5 Mar 2025 17:36:02 +0900 Subject: [PATCH 08/17] get_right_opposite test is strange Signed-off-by: Mamoru Sobue --- common/autoware_lanelet2_utility/README.md | 2 +- .../sample_map/intersection/crossing.osm | 29368 ++++++++-------- .../src/topology.cpp | 8 +- .../test/topology.cpp | 61 +- 4 files changed, 14765 insertions(+), 14674 deletions(-) diff --git a/common/autoware_lanelet2_utility/README.md b/common/autoware_lanelet2_utility/README.md index a84d0b069..1cc259d56 100644 --- a/common/autoware_lanelet2_utility/README.md +++ b/common/autoware_lanelet2_utility/README.md @@ -163,7 +163,7 @@ std::vector forEachMatchInMultiMap(const MapT& map, const KeyT& key, Func&& f | --------------------------- | --------------- | --------------------------------------------------- | | `road_shoulder/highway.osm` | `1` | ![highway](./media/maps/road_shoulder/highway.png) | | `road_shoulder/pudo.osm` | `140` | ![pudo](./media/maps/road_shoulder/pudo.png) | -| `intersection/crossing.osm` | `1867` | ![crossing](./media/maps/intersection/crossing.png) | +| `intersection/crossing.osm` | `1861` | ![crossing](./media/maps/intersection/crossing.png) | ### How to craft test map diff --git a/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm b/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm index ff5184aa7..9030df5a9 100644 --- a/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm +++ b/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm @@ -1,15586 +1,15636 @@ - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - + + + + + - - - - - + + + + + + - - - - - - + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - + + + + + + - - - + + + - - - - - - + + + - - - - - - + + + + + + - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - + + + + + + - - - - - - - - - - + + + - - - - - - - - - - - + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - + + + + + + + + + + + - - - - - - + + + + + + + + - - - - - - + + + + + + - - - - - - - - + + + + + + - - - - - - - - - - - + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + + - - - - - + + + + + + + + + + - - - - - - + + + + + - - - - - + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - - + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - - + + + + + + + + + + + + + + + + + + + - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - + + + - - - - - - - - - - - - - - - - - - - - - - - - - - + + + - - - + + + + + - - - + + + + + - - - - - + + + + + + + + + + + + + + - - - - - + + + + - - - - - - - - - - - - - - + + + - - - - + + + + + - - - + + + - - - - - + + + + + - - - + + + + + - - - - - + + + + + - - - - - + + + + + + - - - - - + + + + + + - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + - - - - - - + + + - - - - - - + + + + + + + + + + + + + - - - + + + + + + + + + + + + + - - - + + + - - - - - - - - - - - - - + + + - - - - - - - - - - - - - + + + - - - + + + + - - - + + + + + - - - + + + + + - - - - + + + + - - - - - + + + + + - - - - - + + + + + - - - - + + + + - - - - + + + + - - - - - + + + + + + + + + - - - - - + + + + - - - - + + + + + - - - - + + + + + + + + + - - - - - - - - - + + + + - - - - + + + + + - - - - - + + + + + + + + + - - - - - - - - - + + + + - - - - + + + + - - - - - + + + + - - - - - - - - - + + + + + - - - - + + + + + + + - - - - + + + + - - - - + + + + + - - - - - + + + + + + + - - - - - - - + + + + - - - - + + + + - - - - - + + + + + - - - - - - - + + + + + + + - - - - + + + + - - - - + + + + + - - - - - + + + + + + + - - - - - - - + + + + - - - - + + + + - - - - - + + + + - - - - - - - + + + + - - - - + + + + + - - - - + + + + + + + - - - - + + + + - - - - + + + + + - - - - - + + + + + + + - - - - - - - + + + + - - - - + + + + + - - - - - + + + + + - - - - - - - + + + + + - - - - + + + + - - - - - + + + + - - - - - + + + + + - - - - - + + + + + - - - - + + + + + - - - - + + + - - - - - + + + + + - - - - - + + + + + + + - - - - - + + + + + + - - - + + + + + + - - - - - + + + + - - - - - - - + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + - - - - - - + + + + + - - - - + + + + - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - + + + + + - - - - - + + + + + + + + + - - - - + + + + - - - - - - + + + + - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + - - - - + + + + - - - - + + + + - - - - - - - - - + + + + + + - - - - - - - - + + + + + + - - - - + + + + - - - - + + + + + + + + - - - - - - + + + + - - - - - - + + + + + + - - - - + + + + + + + - - - - - - - - + + + + - - - - + + + + - - - - - - + + + + + + + - - - - - - - + + + + + - - - - + + + + + + + + + + - - - - + + + + + - - - - - - - + + + + + + + + + + - - - - - + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - - - + + + + - - - - - - - - - - + + + + + + + + - - - - - - - - + + + + - - - - - - - - - - + + + + + + - - - - + + + + + + + - - - - - - - - + + + + - - - - + + + + - - - - - - + + + + + + + - - - - - - - + + + + + - - - - + + + + + + + + + + - - - - + + + + + - - - - - - - + + + + + + + + + + - - - - - + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - - - + + + + + - - - - - - - - - - + + + + - - - - - - - - + + + + + - - - - - - - - - - + + + + - - - - - + + + + - - - - + + + + - - - - - + + + + + + + + + + - - - - + + + + + + + + + + + + + + + + + + + + - - - - + + + + + + + + - - - - + + + + - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - + + + + + + + + + + + - - - - + + + + - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + - - - - - - - - - - - + + + + - - - - + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - + + + + - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - + + + + - - - - - - - - - - - - - - + + + + + + + + + + + - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + - - - - - - - - - - - + + + + - - - - + + + + - - - - - - - - - - - + + + + - - - - + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - - - - + + + + + + + + - - - - - - - - - - - + + + + + + + + - - - - - - - - - - - + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - + + + + + + + + + + + + - - - - - - - - + + + + + + + + + + + + - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + - - - - - - - - - - - - - + + + + + + + + - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - + + + + + + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - + + + + + + + + - - - - - - - + + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - - - + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - + + + + + + + + - - - - - - - + + + + + + + - - - - - - - - + + + + + + + - - - - - - - + + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - + + + + + + + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - - - + + + + + + + - - - + + + + + + + - - - + + + + + + + - - - + + + + + + + - - - - - - - - - - - - - - - + + + + + + + - - - - - - - - + + + + + - - - - - - - - - - - - - - - - - - - - + + + + + + + - - - - - - - - - - - - - - - + + + + + + + - - - - - + + + - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/common/autoware_lanelet2_utility/src/topology.cpp b/common/autoware_lanelet2_utility/src/topology.cpp index c3fa17e2d..1a815b1ba 100644 --- a/common/autoware_lanelet2_utility/src/topology.cpp +++ b/common/autoware_lanelet2_utility/src/topology.cpp @@ -76,9 +76,7 @@ std::optional left_opposite_lanelet( { for (const auto & opposite_candidate : lanelet_map->laneletLayer.findUsages(lanelet.leftBound().invert())) { - if (opposite_candidate.rightBound().id() == lanelet.leftBound().id()) { - return opposite_candidate; - } + return opposite_candidate; } return std::nullopt; } @@ -88,9 +86,7 @@ std::optional right_opposite_lanelet( { for (const auto & opposite_candidate : lanelet_map->laneletLayer.findUsages(lanelet.rightBound().invert())) { - if (opposite_candidate.leftBound().id() == lanelet.rightBound().id()) { - return opposite_candidate; - } + return opposite_candidate; } return std::nullopt; } diff --git a/common/autoware_lanelet2_utility/test/topology.cpp b/common/autoware_lanelet2_utility/test/topology.cpp index e95ac05d9..5e6c90fa2 100644 --- a/common/autoware_lanelet2_utility/test/topology.cpp +++ b/common/autoware_lanelet2_utility/test/topology.cpp @@ -49,37 +49,82 @@ class TestWithIntersectionCrossingMap : public ::testing::Test TEST_F(TestWithIntersectionCrossingMap, LoadCheck) { - const auto point1867 = lanelet_map_ptr_->pointLayer.get(1867); - EXPECT_EQ(point1867.x(), 0.0); - EXPECT_EQ(point1867.y(), 0.0); + const auto point1861 = lanelet_map_ptr_->pointLayer.get(1861); + EXPECT_EQ(point1861.x(), 0.0); + EXPECT_EQ(point1861.y(), 0.0); } TEST_F(TestWithIntersectionCrossingMap, shoulder_lane_is_inaccesible_on_routing_graph) { const auto left = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2395), routing_graph_ptr_); + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2398), routing_graph_ptr_); EXPECT_EQ(left.has_value(), false); } TEST_F(TestWithIntersectionCrossingMap, bicycle_lane_is_inaccesible_on_routing_graph) { const auto left = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2447), routing_graph_ptr_); + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2450), routing_graph_ptr_); EXPECT_EQ(left.has_value(), false); } TEST_F(TestWithIntersectionCrossingMap, left_lanelet_without_lc_permission) { + const auto left = + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2400), routing_graph_ptr_); + EXPECT_EQ(left.value().id(), 2399); +} + +TEST_F(TestWithIntersectionCrossingMap, left_lanelet_with_lc_permission) +{ + const auto left = + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2399), routing_graph_ptr_); + EXPECT_EQ(left.value().id(), 2398); +} + +TEST_F(TestWithIntersectionCrossingMap, right_lanelet_without_lc_permission) +{ + const auto left = + lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2399), routing_graph_ptr_); + EXPECT_EQ(left.value().id(), 2400); +} + +TEST_F(TestWithIntersectionCrossingMap, right_lanelet_with_lc_permission) +{ + const auto left = + lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2398), routing_graph_ptr_); + EXPECT_EQ(left.value().id(), 2399); +} + +TEST_F(TestWithIntersectionCrossingMap, right_opposite_lanelet_null_because_it_is_middle_lane) +{ + const auto right_opposite = lanelet2_utility::right_opposite_lanelet( + lanelet_map_ptr_->laneletLayer.get(2451), lanelet_map_ptr_); + EXPECT_EQ(right_opposite.has_value(), false); +} + +TEST_F(TestWithIntersectionCrossingMap, right_opposite_lanelet_valid) +{ + const auto lanelet = lanelet_map_ptr_->laneletLayer.get(2479); + const auto right_opposite = lanelet2_utility::right_opposite_lanelet(lanelet, lanelet_map_ptr_); + EXPECT_EQ(lanelet_map_ptr_->laneletLayer.findUsages(lanelet.rightBound().invert()).size(), 1); + // EXPECT_EQ(right_opposite.value().id(), lanelet_map_ptr_->laneletLayer.get(2407).id()); +} + +/* +TEST_F(TestWithIntersectionCrossingInverseMap, left_opposite_lanelet_valid) +n{ const auto left = lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2398), routing_graph_ptr_); EXPECT_EQ(left.value().id(), 2397); } -TEST_F(TestWithIntersectionCrossingMap, left_lanelet_with_lc_permission) +TEST_F(TestWithIntersectionCrossingInverseMap, left_opposite_lanelet_null) { const auto left = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2396), routing_graph_ptr_); - EXPECT_EQ(left.value().id(), 2395); + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2398), routing_graph_ptr_); + EXPECT_EQ(left.value().id(), 2397); } +*/ } // namespace autoware From 1c536ed41648ef3143cc4f2f91397ff2c6726da7 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 5 Mar 2025 20:09:20 +0900 Subject: [PATCH 09/17] for opposite lane, use other map Signed-off-by: Mamoru Sobue --- common/autoware_lanelet2_utility/README.md | 4 +- .../sample_map/intersection/crossing.osm | 29331 ++++++++-------- .../test/topology.cpp | 53 +- 3 files changed, 14393 insertions(+), 14995 deletions(-) diff --git a/common/autoware_lanelet2_utility/README.md b/common/autoware_lanelet2_utility/README.md index 1cc259d56..0bbe9f94c 100644 --- a/common/autoware_lanelet2_utility/README.md +++ b/common/autoware_lanelet2_utility/README.md @@ -159,11 +159,13 @@ std::vector forEachMatchInMultiMap(const MapT& map, const KeyT& key, Func&& f ## Test maps +All of the maps are in `local` coordinate. + | Map name | Origin point id | Image | | --------------------------- | --------------- | --------------------------------------------------- | | `road_shoulder/highway.osm` | `1` | ![highway](./media/maps/road_shoulder/highway.png) | | `road_shoulder/pudo.osm` | `140` | ![pudo](./media/maps/road_shoulder/pudo.png) | -| `intersection/crossing.osm` | `1861` | ![crossing](./media/maps/intersection/crossing.png) | +| `intersection/crossing.osm` | `1824` | ![crossing](./media/maps/intersection/crossing.png) | ### How to craft test map diff --git a/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm b/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm index 9030df5a9..66e43e0d4 100644 --- a/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm +++ b/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm @@ -1,15636 +1,15063 @@ - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + + + - - - + + + + + + + + + + + + + + + + + + + + - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - + + + - - - - - + + + - - - - - - + + + + + - - - - - - - - + + + + + - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - + + + + - - - - - - - - - - + + + - - - - + + + + + - - - - - - + + + - - - - - - + + + + + - - - - - - - - - - - - - - - - - - - + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - + + + + + + - - - + + + + + + - - - - - + + + + + + - - - - - + + + + + + - - - - - - - - - - - - - - + + + + + + - - - - + + + + + + - - - + + + + + + - - - - - + + + + + + - - - + + + + + + - - - - - + + + + + + - - - - - + + + + + + - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + - - - - - - + + + - - - - - - + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + - - - - - - + + + - - - - - - + + + - - - - - - + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + - - - - - - + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + - - - - - - + + + + + - - - - - - + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - + + + + + + - - - + + + + + + - - - - - - - - - - - - - + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - + + + + + + + + + + - - - + + + + + - - - + + + + - - - - + + + + + + - - - - - + + + + + - - - - - + + + + + + + + + - - - - + + + + - - - - - + + + + - - - - - + + + + + + + + + - - - - + + + + + + + + - - - - + + + + - - - - - - - - - + + + + - - - - + + + + + + - - - - - + + + + + + - - - - - - - - - + + + + + + + + - - - - + + + + - - - - - + + + + + + - - - - - - - - - + + + + + + + - - - - + + + + - - - - + + + + - - - - + + + + + + + - - - - - + + + + + - - - - - - - + + + + + + + + + + - - - - + + + + + - - - - - + + + + + + + + + + - - - - - - - + + + + + + + + - - - - + + + + + + + + + + - - - - + + + + - - - - - + + + + + + + + - - - - - - - + + + + - - - - + + + + + + - - - - - + + + + + + + - - - - - - - + + + + - - - - + + + + - - - - + + + + + + + - - - - + + + + + - - - - + + + + + + + + + + - - - - - + + + + + - - - - - - - + + + + + + + + + + - - - - + + + + + + + + - - - - - + + + + + + + + + + - - - - - - - + + + + + - - - - + + + + - - - - - + + + + + - - - - - + + + + - - - - - + + + + - - - - + + + + - - - - + + + + + + + + + + - - - - - + + + + + + + + + + + + - - - - - + + + + + + + + - - - - - + + + + - - - + + + + + + + + + + + - - - - - + + + + + + + + + + + - - - - - - - + + + + + + + + + + + - - - - - - + + + + - - - - - - + + + + + + + + + + + + - - - - + + + + + + + + - - - - - - - - - - - - - - + + + + - - - - - - - - - - + + + + + + + + + + + - - - - - + + + + + + + + + + + + - - - - + + + + - - - - - - + + + + + + + + + + + - - - - - + + + + - - - - - - - - - + + + + + + + + + + + + + + - - - - + + + + + + - - - - + + + + + + + + + + + - - - - - - - - - + + + + - - - - - - - - + + + + + + + + + + + - - - - + + + + + + + + + + + - - - - + + + + + + + + + + + - - - - - - + + + + - - - - - - + + + + + + + + + + + - - - - + + + + - - - - - - - - + + + + + + + + + + + - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + +
+ + + + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - + + + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - - - + + + + + + + + - - - - - - - - - + + + + + + + + - - - - - - - - - + + + + + + + + - - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - - + + + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - + + + + - - - - + + + + - - - - + + + + - - - - + + + + - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + - - - - - - + + + + + + - - - - - - - + + + + + + +
diff --git a/common/autoware_lanelet2_utility/test/topology.cpp b/common/autoware_lanelet2_utility/test/topology.cpp index 5e6c90fa2..deacab655 100644 --- a/common/autoware_lanelet2_utility/test/topology.cpp +++ b/common/autoware_lanelet2_utility/test/topology.cpp @@ -49,7 +49,7 @@ class TestWithIntersectionCrossingMap : public ::testing::Test TEST_F(TestWithIntersectionCrossingMap, LoadCheck) { - const auto point1861 = lanelet_map_ptr_->pointLayer.get(1861); + const auto point1861 = lanelet_map_ptr_->pointLayer.get(1824); EXPECT_EQ(point1861.x(), 0.0); EXPECT_EQ(point1861.y(), 0.0); } @@ -57,74 +57,43 @@ TEST_F(TestWithIntersectionCrossingMap, LoadCheck) TEST_F(TestWithIntersectionCrossingMap, shoulder_lane_is_inaccesible_on_routing_graph) { const auto left = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2398), routing_graph_ptr_); + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2341), routing_graph_ptr_); EXPECT_EQ(left.has_value(), false); } TEST_F(TestWithIntersectionCrossingMap, bicycle_lane_is_inaccesible_on_routing_graph) { const auto left = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2450), routing_graph_ptr_); + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2372), routing_graph_ptr_); EXPECT_EQ(left.has_value(), false); } TEST_F(TestWithIntersectionCrossingMap, left_lanelet_without_lc_permission) { const auto left = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2400), routing_graph_ptr_); - EXPECT_EQ(left.value().id(), 2399); + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2335), routing_graph_ptr_); + EXPECT_EQ(left.value().id(), 2334); } TEST_F(TestWithIntersectionCrossingMap, left_lanelet_with_lc_permission) { const auto left = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2399), routing_graph_ptr_); - EXPECT_EQ(left.value().id(), 2398); + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2334), routing_graph_ptr_); + EXPECT_EQ(left.value().id(), 2333); } TEST_F(TestWithIntersectionCrossingMap, right_lanelet_without_lc_permission) { const auto left = - lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2399), routing_graph_ptr_); - EXPECT_EQ(left.value().id(), 2400); + lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2333), routing_graph_ptr_); + EXPECT_EQ(left.value().id(), 2334); } TEST_F(TestWithIntersectionCrossingMap, right_lanelet_with_lc_permission) { const auto left = - lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2398), routing_graph_ptr_); - EXPECT_EQ(left.value().id(), 2399); + lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2334), routing_graph_ptr_); + EXPECT_EQ(left.value().id(), 2335); } -TEST_F(TestWithIntersectionCrossingMap, right_opposite_lanelet_null_because_it_is_middle_lane) -{ - const auto right_opposite = lanelet2_utility::right_opposite_lanelet( - lanelet_map_ptr_->laneletLayer.get(2451), lanelet_map_ptr_); - EXPECT_EQ(right_opposite.has_value(), false); -} - -TEST_F(TestWithIntersectionCrossingMap, right_opposite_lanelet_valid) -{ - const auto lanelet = lanelet_map_ptr_->laneletLayer.get(2479); - const auto right_opposite = lanelet2_utility::right_opposite_lanelet(lanelet, lanelet_map_ptr_); - EXPECT_EQ(lanelet_map_ptr_->laneletLayer.findUsages(lanelet.rightBound().invert()).size(), 1); - // EXPECT_EQ(right_opposite.value().id(), lanelet_map_ptr_->laneletLayer.get(2407).id()); -} - -/* -TEST_F(TestWithIntersectionCrossingInverseMap, left_opposite_lanelet_valid) -n{ - const auto left = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2398), routing_graph_ptr_); - EXPECT_EQ(left.value().id(), 2397); -} - -TEST_F(TestWithIntersectionCrossingInverseMap, left_opposite_lanelet_null) -{ - const auto left = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2398), routing_graph_ptr_); - EXPECT_EQ(left.value().id(), 2397); -} -*/ - } // namespace autoware From 5d5df1b092d535fe411689af1880b7f48425c5a2 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 5 Mar 2025 21:19:01 +0900 Subject: [PATCH 10/17] [Pass] opposite lane is impossible to test Signed-off-by: Mamoru Sobue --- common/autoware_lanelet2_utility/README.md | 3 +- .../autoware_lanelet2_utility/topology.hpp | 6 +- .../sample_map/intersection/T-Shape.osm | 1648 +++++++++++++++++ .../src/topology.cpp | 2 +- .../autoware_lanelet2_utility/test/kind.cpp | 39 +- .../test/topology.cpp | 112 +- 6 files changed, 1781 insertions(+), 29 deletions(-) create mode 100644 common/autoware_lanelet2_utility/sample_map/intersection/T-Shape.osm diff --git a/common/autoware_lanelet2_utility/README.md b/common/autoware_lanelet2_utility/README.md index 0bbe9f94c..2c171958e 100644 --- a/common/autoware_lanelet2_utility/README.md +++ b/common/autoware_lanelet2_utility/README.md @@ -40,7 +40,7 @@ This package aims to strictly define the meaning of several words to clarify the | | `right_opposite_lanelet` | | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | In the first and second map, the green Lanelet is the `right_opposite_lanelet` of the orange Lanelet.
In the third map, the `right_opposite_lanelet` of the orange Lanelet is `null`.
![right_opposite_lanelet](./media/api/right_opposite_lanelet.drawio.svg) | | | `leftmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first and second map, the green Lanelet is the `leftmost_lanelet` of the orange Lanelet.
In the third map, the `leftmost_lanelet` of the orange Lanelet is `null`.
![leftmost_lanelet](./media/api/leftmost_lanelet.drawio.svg) | | | `rightmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelet is the `rightmost_lanelet` of the orange Lanelet.
In the second and third map, the `rightmost_lanelet` of the orange Lanelet is `null`.
![rightmost_lanelet](./media/api/rightmost_lanelet.drawio.svg) | -| | `left_lanelets` | The input Lanelet is not included in the output. | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelete are the `left_lanelets` of the orange Lanelet.
In the second and third map, `left_lanelets` of the orange Lanelet is empty.
![left_lanelets](./media/api/left_lanelets.drawio.svg) | +| | `left_lanelets` | The input Lanelet is not included in the output. | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelets are the `left_lanelets` of the orange Lanelet.
In the second and third map, `left_lanelets` of the orange Lanelet is empty.
![left_lanelets](./media/api/left_lanelets.drawio.svg) | | | `right_lanelets` | same as above `left_lanelets`. | $O(W)$ where $W$ is the size of the `bundle.` | In the first map, the green Lanelets are the `right_lanelets` of the orange Lanelet.
In the second and third map, `right_lanelets` of the orange Lanelet is empty.
![right_lanelets](./media/api/right_lanelets.drawio.svg) | | | `following_lanelets` | | $O(E)$ where $E$ is the number of Lanelets to which the input is connected to. | | | | `previous_lanelets` | | $O(E)$ where $E$ is the number of Lanelets from which the input is connected from. | | @@ -166,6 +166,7 @@ All of the maps are in `local` coordinate. | `road_shoulder/highway.osm` | `1` | ![highway](./media/maps/road_shoulder/highway.png) | | `road_shoulder/pudo.osm` | `140` | ![pudo](./media/maps/road_shoulder/pudo.png) | | `intersection/crossing.osm` | `1824` | ![crossing](./media/maps/intersection/crossing.png) | +| `intersection/T-shape.osm` | `212` | | ### How to craft test map diff --git a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp index 1389437ea..1ea97b8ac 100644 --- a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp +++ b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp @@ -27,7 +27,7 @@ namespace autoware::lanelet2_utility /** * @brief instantiate RoutingGraph from given LaneletMap only from "road" lanes * @param location [in, opt, lanelet::Locations::Germany] location value - * @param particiapnt [in, opt, lanelet::Participants::Vehicle] participant value + * @param participant [in, opt, lanelet::Participants::Vehicle] participant value * @return RoutingGraph object without road_shoulder and bicycle_lane */ lanelet::routing::RoutingGraphConstPtr instantiate_routing_graph( @@ -60,7 +60,7 @@ std::optional right_lanelet( * lanelet is limited to the one with same turn_direction value * @param [in] lanelet input lanelet * @param [in] routing_graph routing_graph containing `lanelet` - * @return optional of abovementioned lanelet(nullopt if there is no such lanelet) + * @return optional of aforementioned lanelet(nullopt if there is no such lanelet) */ /* std::optional left_similar_lanelet( @@ -73,7 +73,7 @@ const lanelet::routing::RoutingGraphConstPtr routing_graph); * sibling lanelet is limited to the one with same turn_direction value * @param [in] lanelet input lanelet * @param [in] routing_graph routing_graph containing `lanelet` - * @return optional of abovementioned lanelet(nullopt if there is no such lanelet) + * @return optional of aforementioned lanelet(nullopt if there is no such lanelet) */ /* std::optional right_similar_lanelet( diff --git a/common/autoware_lanelet2_utility/sample_map/intersection/T-Shape.osm b/common/autoware_lanelet2_utility/sample_map/intersection/T-Shape.osm new file mode 100644 index 000000000..c5832c58b --- /dev/null +++ b/common/autoware_lanelet2_utility/sample_map/intersection/T-Shape.osm @@ -0,0 +1,1648 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/src/topology.cpp b/common/autoware_lanelet2_utility/src/topology.cpp index 1a815b1ba..42693ffae 100644 --- a/common/autoware_lanelet2_utility/src/topology.cpp +++ b/common/autoware_lanelet2_utility/src/topology.cpp @@ -124,7 +124,7 @@ std::optional rightmost_lanelet( } size_t bundle_size_diagnosis = 0; while (bundle_size_diagnosis < k_normal_bundle_max_size) { - const auto next_right_lane = left_lanelet(right_lane.value(), routing_graph); + const auto next_right_lane = right_lanelet(right_lane.value(), routing_graph); if (!next_right_lane) { // reached return right_lane; diff --git a/common/autoware_lanelet2_utility/test/kind.cpp b/common/autoware_lanelet2_utility/test/kind.cpp index d2fad85ca..ea72ae78c 100644 --- a/common/autoware_lanelet2_utility/test/kind.cpp +++ b/common/autoware_lanelet2_utility/test/kind.cpp @@ -26,6 +26,8 @@ namespace fs = std::filesystem; +namespace autoware +{ class TestWithRoadShoulderHighwayMap : public ::testing::Test { protected: @@ -42,6 +44,22 @@ class TestWithRoadShoulderHighwayMap : public ::testing::Test } }; +class TestWithIntersectionCrossingMap : public ::testing::Test +{ +protected: + lanelet::LaneletMapConstPtr lanelet_map_ptr_{nullptr}; + + void SetUp() override + { + const auto sample_map_dir = + fs::path(ament_index_cpp::get_package_share_directory("autoware_lanelet2_utility")) / + "sample_map"; + const auto road_shoulder_highway_map_path = sample_map_dir / "intersection" / "crossing.osm"; + + lanelet_map_ptr_ = load_local_coordinate_map(road_shoulder_highway_map_path.string()); + } +}; + TEST_F(TestWithRoadShoulderHighwayMap, LoadCheck) { const auto point8 = lanelet_map_ptr_->pointLayer.get(1); @@ -58,20 +76,27 @@ TEST_F(TestWithRoadShoulderHighwayMap, LoadCheck) TEST_F(TestWithRoadShoulderHighwayMap, is_road_lane) { const auto ll = lanelet_map_ptr_->laneletLayer.get(47); - EXPECT_EQ(autoware::lanelet2_utility::is_road_lane(ll), true); - EXPECT_EQ(autoware::lanelet2_utility::is_shoulder_lane(ll), false); - EXPECT_EQ(autoware::lanelet2_utility::is_bicycle_lane(ll), false); + EXPECT_EQ(lanelet2_utility::is_road_lane(ll), true); + EXPECT_EQ(lanelet2_utility::is_shoulder_lane(ll), false); + EXPECT_EQ(lanelet2_utility::is_bicycle_lane(ll), false); } TEST_F(TestWithRoadShoulderHighwayMap, is_shoulder_lane) { const auto ll = lanelet_map_ptr_->laneletLayer.get(44); - EXPECT_EQ(autoware::lanelet2_utility::is_road_lane(ll), false); - EXPECT_EQ(autoware::lanelet2_utility::is_shoulder_lane(ll), true); - EXPECT_EQ(autoware::lanelet2_utility::is_bicycle_lane(ll), false); + EXPECT_EQ(lanelet2_utility::is_road_lane(ll), false); + EXPECT_EQ(lanelet2_utility::is_shoulder_lane(ll), true); + EXPECT_EQ(lanelet2_utility::is_bicycle_lane(ll), false); } -// TODO(soblin): add and use bicycle lane map +TEST_F(TestWithIntersectionCrossingMap, is_shoulder_lane) +{ + const auto ll = lanelet_map_ptr_->laneletLayer.get(2392); + EXPECT_EQ(lanelet2_utility::is_road_lane(ll), false); + EXPECT_EQ(lanelet2_utility::is_shoulder_lane(ll), false); + EXPECT_EQ(lanelet2_utility::is_bicycle_lane(ll), true); +} +} // namespace autoware int main(int argc, char ** argv) { diff --git a/common/autoware_lanelet2_utility/test/topology.cpp b/common/autoware_lanelet2_utility/test/topology.cpp index deacab655..e289a978a 100644 --- a/common/autoware_lanelet2_utility/test/topology.cpp +++ b/common/autoware_lanelet2_utility/test/topology.cpp @@ -49,51 +49,129 @@ class TestWithIntersectionCrossingMap : public ::testing::Test TEST_F(TestWithIntersectionCrossingMap, LoadCheck) { - const auto point1861 = lanelet_map_ptr_->pointLayer.get(1824); - EXPECT_EQ(point1861.x(), 0.0); - EXPECT_EQ(point1861.y(), 0.0); + const auto point = lanelet_map_ptr_->pointLayer.get(1824); + EXPECT_EQ(point.x(), 0.0); + EXPECT_EQ(point.y(), 0.0); } -TEST_F(TestWithIntersectionCrossingMap, shoulder_lane_is_inaccesible_on_routing_graph) +TEST_F(TestWithIntersectionCrossingMap, shoulder_lane_is_inaccessible_on_routing_graph) { - const auto left = + const auto lane = lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2341), routing_graph_ptr_); - EXPECT_EQ(left.has_value(), false); + EXPECT_EQ(lane.has_value(), false); } -TEST_F(TestWithIntersectionCrossingMap, bicycle_lane_is_inaccesible_on_routing_graph) +TEST_F(TestWithIntersectionCrossingMap, bicycle_lane_is_inaccessible_on_routing_graph) { - const auto left = + const auto lane = lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2372), routing_graph_ptr_); - EXPECT_EQ(left.has_value(), false); + EXPECT_EQ(lane.has_value(), false); } TEST_F(TestWithIntersectionCrossingMap, left_lanelet_without_lc_permission) { - const auto left = + const auto lane = lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2335), routing_graph_ptr_); - EXPECT_EQ(left.value().id(), 2334); + EXPECT_EQ(lane.value().id(), 2334); } TEST_F(TestWithIntersectionCrossingMap, left_lanelet_with_lc_permission) { - const auto left = + const auto lane = lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2334), routing_graph_ptr_); - EXPECT_EQ(left.value().id(), 2333); + EXPECT_EQ(lane.value().id(), 2333); } TEST_F(TestWithIntersectionCrossingMap, right_lanelet_without_lc_permission) { - const auto left = + const auto lane = lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2333), routing_graph_ptr_); - EXPECT_EQ(left.value().id(), 2334); + EXPECT_EQ(lane.value().id(), 2334); } TEST_F(TestWithIntersectionCrossingMap, right_lanelet_with_lc_permission) { - const auto left = + const auto lane = lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2334), routing_graph_ptr_); - EXPECT_EQ(left.value().id(), 2335); + EXPECT_EQ(lane.value().id(), 2335); } +TEST_F(TestWithIntersectionCrossingMap, leftmost_lanelet_valid) +{ + const auto lane = lanelet2_utility::leftmost_lanelet( + lanelet_map_ptr_->laneletLayer.get(2335), routing_graph_ptr_); + EXPECT_EQ(lane.value().id(), 2333); +} + +TEST_F(TestWithIntersectionCrossingMap, leftmost_lanelet_null) +{ + const auto lane = lanelet2_utility::leftmost_lanelet( + lanelet_map_ptr_->laneletLayer.get(2333), routing_graph_ptr_); + EXPECT_EQ(lane.has_value(), false); +} + +TEST_F(TestWithIntersectionCrossingMap, rightmost_lanelet_valid) +{ + const auto lane = lanelet2_utility::rightmost_lanelet( + lanelet_map_ptr_->laneletLayer.get(2333), routing_graph_ptr_); + EXPECT_EQ(lane.value().id(), 2337); +} + +TEST_F(TestWithIntersectionCrossingMap, rightmost_lanelet_null) +{ + const auto lane = lanelet2_utility::rightmost_lanelet( + lanelet_map_ptr_->laneletLayer.get(2337), routing_graph_ptr_); + EXPECT_EQ(lane.has_value(), false); +} + +TEST_F(TestWithIntersectionCrossingMap, left_lanelets_without_opposite) +{ + const auto lefts = lanelet2_utility::left_lanelets( + lanelet_map_ptr_->laneletLayer.get(2344), lanelet_map_ptr_, routing_graph_ptr_); + EXPECT_EQ(lefts.size(), 3); + EXPECT_EQ(lefts[0].id(), 2343); + EXPECT_EQ(lefts[1].id(), 2342); + EXPECT_EQ(lefts[2].id(), 2341); +} + +TEST_F(TestWithIntersectionCrossingMap, right_lanelets_without_opposite) +{ + const auto lefts = lanelet2_utility::right_lanelets( + lanelet_map_ptr_->laneletLayer.get(2341), lanelet_map_ptr_, routing_graph_ptr_); + EXPECT_EQ(lefts.size(), 3); + EXPECT_EQ(lefts[0].id(), 2342); + EXPECT_EQ(lefts[1].id(), 2343); + EXPECT_EQ(lefts[2].id(), 2344); +} + +class TestWithIntersection_T_ShapeMap : public ::testing::Test +{ +protected: + lanelet::LaneletMapConstPtr lanelet_map_ptr_{nullptr}; + lanelet::routing::RoutingGraphConstPtr routing_graph_ptr_{nullptr}; + + void SetUp() override + { + const auto sample_map_dir = + fs::path(ament_index_cpp::get_package_share_directory("autoware_lanelet2_utility")) / + "sample_map"; + const auto intersection_t_shape_map_path = sample_map_dir / "intersection" / "T-Shape.osm"; + + lanelet_map_ptr_ = load_local_coordinate_map(intersection_t_shape_map_path.string()); + routing_graph_ptr_ = lanelet2_utility::instantiate_routing_graph(lanelet_map_ptr_); + } +}; + +TEST_F(TestWithIntersection_T_ShapeMap, LoadCheck) +{ + const auto point = lanelet_map_ptr_->pointLayer.get(212); + EXPECT_EQ(point.x(), 0.0); + EXPECT_EQ(point.y(), 0.0); +} } // namespace autoware + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} From 46b280d02540d5b9ab20f5dd4b72d1e08f12662a Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 6 Mar 2025 16:44:04 +0900 Subject: [PATCH 11/17] updated map to MGRS Signed-off-by: Mamoru Sobue --- common/autoware_lanelet2_utility/README.md | 7 +- common/autoware_lanelet2_utility/package.xml | 1 + .../sample_map/intersection/T-Shape.osm | 1648 - .../sample_map/intersection/crossing.osm | 28390 ++++++++-------- .../intersection/crossing_fms_original.osm | 14533 ++++++++ .../sample_map/road_shoulder/fms.osm | 3464 ++ .../sample_map/road_shoulder/highway.osm | 270 +- .../sample_map/road_shoulder/pudo.osm | 3151 +- .../scripts/lanelet_anonymizer.py | 14 +- .../autoware_lanelet2_utility/test/kind.cpp | 26 +- .../{local_projector.hpp => map_loader.hpp} | 33 +- .../test/topology.cpp | 83 +- 12 files changed, 34394 insertions(+), 17226 deletions(-) delete mode 100644 common/autoware_lanelet2_utility/sample_map/intersection/T-Shape.osm create mode 100644 common/autoware_lanelet2_utility/sample_map/intersection/crossing_fms_original.osm create mode 100644 common/autoware_lanelet2_utility/sample_map/road_shoulder/fms.osm rename common/autoware_lanelet2_utility/test/{local_projector.hpp => map_loader.hpp} (52%) diff --git a/common/autoware_lanelet2_utility/README.md b/common/autoware_lanelet2_utility/README.md index 2c171958e..ede576760 100644 --- a/common/autoware_lanelet2_utility/README.md +++ b/common/autoware_lanelet2_utility/README.md @@ -165,18 +165,17 @@ All of the maps are in `local` coordinate. | --------------------------- | --------------- | --------------------------------------------------- | | `road_shoulder/highway.osm` | `1` | ![highway](./media/maps/road_shoulder/highway.png) | | `road_shoulder/pudo.osm` | `140` | ![pudo](./media/maps/road_shoulder/pudo.png) | -| `intersection/crossing.osm` | `1824` | ![crossing](./media/maps/intersection/crossing.png) | -| `intersection/T-shape.osm` | `212` | | +| `intersection/crossing.osm` | `1791` | ![crossing](./media/maps/intersection/crossing.png) | ### How to craft test map -On the VMB, create the map in local projector(or convert it to local projector from MGRS projector) and save the file as ``. Next, select the point to use as (0.0, 0.0) and pass its `` and run +On the VMB, create the map in MGRS system and save the file as ``. Next, select the point to set (100.0, 100.0) and pass its `` and run ```bash ros2 run autoware_lanelet2_utility lanelet_anonymizer.py ``` -Then the coordinate of the specified point is (0, 0) on the loaded map. +Then the coordinate of the specified point is (100, 100) on the loaded map(NOTE: not exactly (0, 0) because MGRS does not any point to have negative coordinate value). By applying `lanelet_id_aligner.py`, the primitive ids are aligned to start from 1 and increase one-by-one. diff --git a/common/autoware_lanelet2_utility/package.xml b/common/autoware_lanelet2_utility/package.xml index 7ca1cbd52..d526dbeea 100644 --- a/common/autoware_lanelet2_utility/package.xml +++ b/common/autoware_lanelet2_utility/package.xml @@ -13,6 +13,7 @@ autoware_cmake autoware_lanelet2_extension + range-v3 rclcpp visualization_msgs diff --git a/common/autoware_lanelet2_utility/sample_map/intersection/T-Shape.osm b/common/autoware_lanelet2_utility/sample_map/intersection/T-Shape.osm deleted file mode 100644 index c5832c58b..000000000 --- a/common/autoware_lanelet2_utility/sample_map/intersection/T-Shape.osm +++ /dev/null @@ -1,1648 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm b/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm index 66e43e0d4..383c4e489 100644 --- a/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm +++ b/common/autoware_lanelet2_utility/sample_map/intersection/crossing.osm @@ -1,15063 +1,14523 @@ - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - + + + - - - - - - - - - - - - - + + + + + - - - - - - - - - - - - - + + + - - - - - - + + + + + - - - - - - - - - - + + + + + - - - - - - - - - - - + + + + + + - - - - - - - - - - - + + + + + + - - - - - - - - - - + + + + + + - - - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - - - + + + + + + - - - - - - - - - - - + + + + + + - - - - - - - - - - - + + + + + + - - - - - - - - - - - + + + + + + - - - - - - - - - - - + + + + + + - - - - - - - - - - + + + + + + - - - - - - - - + + + + + + - - - - - - - - - - - + + + + + + - - - - - - - - - - - + + + + + + - - - - - - - - - - + + + + + + - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - - + + + + + + - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - + + + + + + - - - + + + + + + - - - - - + + + + + + - - - - - + + + + + + - - - - - - - - - - - - - - + + + + + + - - - - + + + + + + - - - + + + + + + - - - - - + + + + + + - - - + + + + + + - - - - - + + + + + + - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + - - - - - - + + + - - - - - - + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + - - - - - - + + + - - - - - - + + + - - - - - - + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + - - - - - - + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + - - - - - - + + + + + - - - - - - + + + + + - - - - - - + + + - - - - - - + + + + + - - - - - - + + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + - - - - - - + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + - - - - - - + + + + + - - - - - - + + + + - - - - - - + + + + + + - - - - - - + + + + + - - - - - - + + + + + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + + + + + - - - - - - + + + + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - + + + + + + + + - - - - - - + + + + - - - - - - + + + + + + - - - - - - + + + + + + + - - - - - - + + + + - - - - - - + + + + - - - - - - + + + + + + + - - - + + + + + - - - + + + + + + + + + + - - - - - - - - - - - - - + + + + + - - - - - - - - - - - - - + + + + + + + + + + - - - + + + + + + + + - - - + + + + + + + + + + - - - + + + + - - - - + + + + + + + + - - - - - + + + + - - - - - + + + + + + - - - - + + + + + + + - - - - + + + + - - - - - + + + + - - - - - + + + + + + + - - - - + + + + + - - - - + + + + + + + + + + - - - - - - - - - + + + + + - - - - + + + + + + + + + + - - - - - + + + + + + + + - - - - - - - - - + + + + + + + + + + - - - - + + + + + - - - - - + + + + - - - - - - - - - + + + + + - - - - + + + + - - - - + + + + - - - - + + + + - - - - - + + + + + + + + + + - - - - - - - + + + + + + + + - - - - + + + + + + + + + + + - - - - - + + + + + + + + + + + - - - - - - - + + + + + + + + + + + - - - - + + + + - - - - + + + + + + + + + + + + - - - - - + + + + + + + + - - - - - - - + + + + - - - - + + + + + + + + + + + - - - - - + + + + + + + + + + + + - - - - - - - + + + + - - - - + + + + + + + + + + + - - - - + + + + - - - - + + + + + + + + + + + + + + - - - - + + + + + + - - - - - + + + + + + + + + + + - - - - - - - + + + + - - - - + + + + + + + - - - - - + + + + + - - - - - - - + + + + - - - - + + + + + - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - - + + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - - - + + + + + + + + - - - - - - + + + + + + + + - - - - - - - - + + + + + + - - - - - - - - + + + + + + + + - - - - + + + + + + + + - - - - + + + + - - - - + + + + - - - - + + + + - - - - - - - - - - - - - - - - + + + + - - - - - - - - - + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + - - - - - - - + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/sample_map/intersection/crossing_fms_original.osm b/common/autoware_lanelet2_utility/sample_map/intersection/crossing_fms_original.osm new file mode 100644 index 000000000..f91599594 --- /dev/null +++ b/common/autoware_lanelet2_utility/sample_map/intersection/crossing_fms_original.osm @@ -0,0 +1,14533 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/sample_map/road_shoulder/fms.osm b/common/autoware_lanelet2_utility/sample_map/road_shoulder/fms.osm new file mode 100644 index 000000000..3c652586d --- /dev/null +++ b/common/autoware_lanelet2_utility/sample_map/road_shoulder/fms.osm @@ -0,0 +1,3464 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm b/common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm index 6643880a5..c65d925bb 100644 --- a/common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm +++ b/common/autoware_lanelet2_utility/sample_map/road_shoulder/highway.osm @@ -1,295 +1,302 @@ - - - - + + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - + + + + + + + + + + + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - - - + + + + + + + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - - - - - - - - - - + + + - + @@ -298,16 +305,16 @@ - - - + + + - + @@ -316,16 +323,16 @@ - - - + + + - + @@ -334,9 +341,18 @@ - - - + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm b/common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm index 56aa7b9bc..65a63f400 100644 --- a/common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm +++ b/common/autoware_lanelet2_utility/sample_map/road_shoulder/pudo.osm @@ -1,1172 +1,1967 @@ - + - - - - + + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -1181,7 +1976,7 @@ - + @@ -1198,7 +1993,7 @@ - + @@ -1213,7 +2008,7 @@ - + @@ -1230,7 +2025,7 @@ - + @@ -1245,7 +2040,7 @@ - + @@ -1262,7 +2057,7 @@ - + @@ -1277,7 +2072,7 @@ - + @@ -1294,7 +2089,7 @@ - + @@ -1309,7 +2104,7 @@ - + @@ -1326,171 +2121,467 @@ - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + + + + - - - - - - - - - - + + + - - - - - - - - - - + + + + + + - - - - - - - - - - + + + + - - - - - - - - - - + + + - - - - - - - - - - + + + - - - - - - - - - - + + + - - - + + + - - - + + + + + + - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + @@ -1499,7 +2590,7 @@ - + @@ -1508,7 +2599,7 @@ - + @@ -1528,7 +2619,7 @@ - + @@ -1542,7 +2633,7 @@ - + @@ -1555,100 +2646,160 @@ - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - - + + + + - - - - + + + + - - - + + + - - - + + + @@ -1656,9 +2807,9 @@ - - - + + + @@ -1666,37 +2817,37 @@ - - - + + + - - - + + + - - - - + + + + - - - + + + @@ -1704,9 +2855,9 @@ - - - + + + @@ -1714,9 +2865,9 @@ - - - + + + @@ -1724,9 +2875,67 @@ - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -1734,19 +2943,163 @@ - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - + + + - - + + diff --git a/common/autoware_lanelet2_utility/scripts/lanelet_anonymizer.py b/common/autoware_lanelet2_utility/scripts/lanelet_anonymizer.py index 3b77b9533..06854c935 100755 --- a/common/autoware_lanelet2_utility/scripts/lanelet_anonymizer.py +++ b/common/autoware_lanelet2_utility/scripts/lanelet_anonymizer.py @@ -17,8 +17,8 @@ import argparse import xml.etree.ElementTree as ET -origin_offset_x = 0.0 -origin_offset_y = 0.0 +origin_x = 100.0 +origin_y = 100.0 def update_osm_latlon(osm_file, output_file, origin_id): @@ -33,8 +33,8 @@ def update_osm_latlon(osm_file, output_file, origin_id): if node.attrib["id"] == str(origin_id): old_origin_local_xy = (float(local_x_tag.attrib["v"]), float(local_y_tag.attrib["v"])) - local_x_tag.set("v", str(0.0 - origin_offset_x)) - local_y_tag.set("v", str(0.0 - origin_offset_y)) + local_x_tag.set("v", str(origin_x)) + local_y_tag.set("v", str(origin_y)) break if old_origin_local_xy is None: @@ -55,10 +55,8 @@ def update_osm_latlon(osm_file, output_file, origin_id): adj_local_x = local_x - old_origin_x adj_local_y = local_y - old_origin_y - local_x_tag.set("v", str(adj_local_x - origin_offset_x)) - local_y_tag.set("v", str(adj_local_y - origin_offset_y)) - node.set("lat", str(0.0)) - node.set("lon", str(0.0)) + local_x_tag.set("v", str(origin_x + adj_local_x)) + local_y_tag.set("v", str(origin_y + adj_local_y)) tree.write(output_file, encoding="UTF-8", xml_declaration=True) print(f"Updated OSM file created: {output_file}") diff --git a/common/autoware_lanelet2_utility/test/kind.cpp b/common/autoware_lanelet2_utility/test/kind.cpp index ea72ae78c..d9c66898a 100644 --- a/common/autoware_lanelet2_utility/test/kind.cpp +++ b/common/autoware_lanelet2_utility/test/kind.cpp @@ -12,14 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "local_projector.hpp" +#include "map_loader.hpp" #include -#include #include #include -#include #include #include @@ -40,7 +38,7 @@ class TestWithRoadShoulderHighwayMap : public ::testing::Test "sample_map"; const auto road_shoulder_highway_map_path = sample_map_dir / "road_shoulder" / "highway.osm"; - lanelet_map_ptr_ = load_local_coordinate_map(road_shoulder_highway_map_path.string()); + lanelet_map_ptr_ = load_mgrs_coordinate_map(road_shoulder_highway_map_path.string()); } }; @@ -56,26 +54,20 @@ class TestWithIntersectionCrossingMap : public ::testing::Test "sample_map"; const auto road_shoulder_highway_map_path = sample_map_dir / "intersection" / "crossing.osm"; - lanelet_map_ptr_ = load_local_coordinate_map(road_shoulder_highway_map_path.string()); + lanelet_map_ptr_ = load_mgrs_coordinate_map(road_shoulder_highway_map_path.string()); } }; TEST_F(TestWithRoadShoulderHighwayMap, LoadCheck) { - const auto point8 = lanelet_map_ptr_->pointLayer.get(1); - EXPECT_EQ(point8.x(), 0.0); - EXPECT_EQ(point8.y(), 0.0); - const auto point10 = lanelet_map_ptr_->pointLayer.get(2); - EXPECT_EQ(point10.x(), 4.0); - EXPECT_EQ(point10.y(), 0.0); - const auto point15 = lanelet_map_ptr_->pointLayer.get(3); - EXPECT_EQ(point15.x(), 8.0); - EXPECT_EQ(point15.y(), 0.0); + const auto point = lanelet_map_ptr_->pointLayer.get(1); + EXPECT_NEAR(point.x(), 100.0, 0.05); + EXPECT_NEAR(point.y(), 100.0, 0.05); } TEST_F(TestWithRoadShoulderHighwayMap, is_road_lane) { - const auto ll = lanelet_map_ptr_->laneletLayer.get(47); + const auto ll = lanelet_map_ptr_->laneletLayer.get(46); EXPECT_EQ(lanelet2_utility::is_road_lane(ll), true); EXPECT_EQ(lanelet2_utility::is_shoulder_lane(ll), false); EXPECT_EQ(lanelet2_utility::is_bicycle_lane(ll), false); @@ -83,7 +75,7 @@ TEST_F(TestWithRoadShoulderHighwayMap, is_road_lane) TEST_F(TestWithRoadShoulderHighwayMap, is_shoulder_lane) { - const auto ll = lanelet_map_ptr_->laneletLayer.get(44); + const auto ll = lanelet_map_ptr_->laneletLayer.get(47); EXPECT_EQ(lanelet2_utility::is_road_lane(ll), false); EXPECT_EQ(lanelet2_utility::is_shoulder_lane(ll), true); EXPECT_EQ(lanelet2_utility::is_bicycle_lane(ll), false); @@ -91,7 +83,7 @@ TEST_F(TestWithRoadShoulderHighwayMap, is_shoulder_lane) TEST_F(TestWithIntersectionCrossingMap, is_shoulder_lane) { - const auto ll = lanelet_map_ptr_->laneletLayer.get(2392); + const auto ll = lanelet_map_ptr_->laneletLayer.get(2303); EXPECT_EQ(lanelet2_utility::is_road_lane(ll), false); EXPECT_EQ(lanelet2_utility::is_shoulder_lane(ll), false); EXPECT_EQ(lanelet2_utility::is_bicycle_lane(ll), true); diff --git a/common/autoware_lanelet2_utility/test/local_projector.hpp b/common/autoware_lanelet2_utility/test/map_loader.hpp similarity index 52% rename from common/autoware_lanelet2_utility/test/local_projector.hpp rename to common/autoware_lanelet2_utility/test/map_loader.hpp index 00e56e8cb..d173b583b 100644 --- a/common/autoware_lanelet2_utility/test/local_projector.hpp +++ b/common/autoware_lanelet2_utility/test/map_loader.hpp @@ -12,8 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LOCAL_PROJECTOR_HPP_ -#define LOCAL_PROJECTOR_HPP_ +#ifndef MAP_LOADER_HPP_ +#define MAP_LOADER_HPP_ + +#include #include #include @@ -22,33 +24,12 @@ #include #include -class LocalProjector : public lanelet::Projector -{ -public: - LocalProjector() : Projector(lanelet::Origin(lanelet::GPSPoint{})) {} - - lanelet::BasicPoint3d forward(const lanelet::GPSPoint & gps) const override // NOLINT - { - return lanelet::BasicPoint3d{0.0, 0.0, gps.ele}; - } - - [[nodiscard]] lanelet::GPSPoint reverse(const lanelet::BasicPoint3d & point) const override - { - return lanelet::GPSPoint{0.0, 0.0, point.z()}; - } -}; - -inline lanelet::LaneletMapConstPtr load_local_coordinate_map(const std::string & path) +inline lanelet::LaneletMapConstPtr load_mgrs_coordinate_map(const std::string & path) { lanelet::ErrorMessages errors{}; - LocalProjector projector; + lanelet::projection::MGRSProjector projector; auto lanelet_map_ptr_mut = lanelet::load(path, projector, &errors); - for (auto point : lanelet_map_ptr_mut->pointLayer) { - point.x() = point.attribute("local_x").asDouble().value(); - point.y() = point.attribute("local_y").asDouble().value(); - } - return lanelet::LaneletMapConstPtr{std::move(lanelet_map_ptr_mut)}; } -#endif // LOCAL_PROJECTOR_HPP_ +#endif // MAP_LOADER_HPP_ diff --git a/common/autoware_lanelet2_utility/test/topology.cpp b/common/autoware_lanelet2_utility/test/topology.cpp index e289a978a..1e59fcaa1 100644 --- a/common/autoware_lanelet2_utility/test/topology.cpp +++ b/common/autoware_lanelet2_utility/test/topology.cpp @@ -12,16 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "local_projector.hpp" +#include "map_loader.hpp" #include -#include #include +#include #include #include #include +#include #include namespace fs = std::filesystem; @@ -42,108 +43,125 @@ class TestWithIntersectionCrossingMap : public ::testing::Test "sample_map"; const auto intersection_crossing_map_path = sample_map_dir / "intersection" / "crossing.osm"; - lanelet_map_ptr_ = load_local_coordinate_map(intersection_crossing_map_path.string()); + lanelet_map_ptr_ = load_mgrs_coordinate_map(intersection_crossing_map_path.string()); routing_graph_ptr_ = lanelet2_utility::instantiate_routing_graph(lanelet_map_ptr_); } }; TEST_F(TestWithIntersectionCrossingMap, LoadCheck) { - const auto point = lanelet_map_ptr_->pointLayer.get(1824); - EXPECT_EQ(point.x(), 0.0); - EXPECT_EQ(point.y(), 0.0); + const auto point = lanelet_map_ptr_->pointLayer.get(1791); + EXPECT_NEAR(point.x(), 100.0, 0.05); + EXPECT_NEAR(point.y(), 100.0, 0.05); } TEST_F(TestWithIntersectionCrossingMap, shoulder_lane_is_inaccessible_on_routing_graph) { const auto lane = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2341), routing_graph_ptr_); + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2257), routing_graph_ptr_); EXPECT_EQ(lane.has_value(), false); } TEST_F(TestWithIntersectionCrossingMap, bicycle_lane_is_inaccessible_on_routing_graph) { const auto lane = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2372), routing_graph_ptr_); + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2286), routing_graph_ptr_); EXPECT_EQ(lane.has_value(), false); } TEST_F(TestWithIntersectionCrossingMap, left_lanelet_without_lc_permission) { const auto lane = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2335), routing_graph_ptr_); - EXPECT_EQ(lane.value().id(), 2334); + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2246), routing_graph_ptr_); + EXPECT_EQ(lane.value().id(), 2245); } TEST_F(TestWithIntersectionCrossingMap, left_lanelet_with_lc_permission) { const auto lane = - lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2334), routing_graph_ptr_); - EXPECT_EQ(lane.value().id(), 2333); + lanelet2_utility::left_lanelet(lanelet_map_ptr_->laneletLayer.get(2245), routing_graph_ptr_); + EXPECT_EQ(lane.value().id(), 2244); } TEST_F(TestWithIntersectionCrossingMap, right_lanelet_without_lc_permission) { const auto lane = - lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2333), routing_graph_ptr_); - EXPECT_EQ(lane.value().id(), 2334); + lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2245), routing_graph_ptr_); + EXPECT_EQ(lane.value().id(), 2246); } TEST_F(TestWithIntersectionCrossingMap, right_lanelet_with_lc_permission) { const auto lane = - lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2334), routing_graph_ptr_); - EXPECT_EQ(lane.value().id(), 2335); + lanelet2_utility::right_lanelet(lanelet_map_ptr_->laneletLayer.get(2244), routing_graph_ptr_); + EXPECT_EQ(lane.value().id(), 2245); +} + +TEST_F(TestWithIntersectionCrossingMap, right_opposite_lanelet) +{ + const auto lane = lanelet2_utility::right_opposite_lanelet( + lanelet_map_ptr_->laneletLayer.get(2288), lanelet_map_ptr_); + EXPECT_EQ(lane.value().id(), 2311); } TEST_F(TestWithIntersectionCrossingMap, leftmost_lanelet_valid) { const auto lane = lanelet2_utility::leftmost_lanelet( - lanelet_map_ptr_->laneletLayer.get(2335), routing_graph_ptr_); - EXPECT_EQ(lane.value().id(), 2333); + lanelet_map_ptr_->laneletLayer.get(2288), routing_graph_ptr_); + EXPECT_EQ(lane.value().id(), 2286); } TEST_F(TestWithIntersectionCrossingMap, leftmost_lanelet_null) { const auto lane = lanelet2_utility::leftmost_lanelet( - lanelet_map_ptr_->laneletLayer.get(2333), routing_graph_ptr_); + lanelet_map_ptr_->laneletLayer.get(2286), routing_graph_ptr_); EXPECT_EQ(lane.has_value(), false); } TEST_F(TestWithIntersectionCrossingMap, rightmost_lanelet_valid) { const auto lane = lanelet2_utility::rightmost_lanelet( - lanelet_map_ptr_->laneletLayer.get(2333), routing_graph_ptr_); - EXPECT_EQ(lane.value().id(), 2337); + lanelet_map_ptr_->laneletLayer.get(2286), routing_graph_ptr_); + EXPECT_EQ(lane.value().id(), 2288); } TEST_F(TestWithIntersectionCrossingMap, rightmost_lanelet_null) { const auto lane = lanelet2_utility::rightmost_lanelet( - lanelet_map_ptr_->laneletLayer.get(2337), routing_graph_ptr_); + lanelet_map_ptr_->laneletLayer.get(2288), routing_graph_ptr_); EXPECT_EQ(lane.has_value(), false); } TEST_F(TestWithIntersectionCrossingMap, left_lanelets_without_opposite) { const auto lefts = lanelet2_utility::left_lanelets( - lanelet_map_ptr_->laneletLayer.get(2344), lanelet_map_ptr_, routing_graph_ptr_); - EXPECT_EQ(lefts.size(), 3); - EXPECT_EQ(lefts[0].id(), 2343); - EXPECT_EQ(lefts[1].id(), 2342); - EXPECT_EQ(lefts[2].id(), 2341); + lanelet_map_ptr_->laneletLayer.get(2288), lanelet_map_ptr_, routing_graph_ptr_); + EXPECT_EQ(lefts.size(), 2); + EXPECT_EQ(lefts[0].id(), 2287); + EXPECT_EQ(lefts[1].id(), 2286); } TEST_F(TestWithIntersectionCrossingMap, right_lanelets_without_opposite) { const auto lefts = lanelet2_utility::right_lanelets( - lanelet_map_ptr_->laneletLayer.get(2341), lanelet_map_ptr_, routing_graph_ptr_); - EXPECT_EQ(lefts.size(), 3); - EXPECT_EQ(lefts[0].id(), 2342); - EXPECT_EQ(lefts[1].id(), 2343); - EXPECT_EQ(lefts[2].id(), 2344); + lanelet_map_ptr_->laneletLayer.get(2286), lanelet_map_ptr_, routing_graph_ptr_); + EXPECT_EQ(lefts.size(), 2); + EXPECT_EQ(lefts[0].id(), 2287); + EXPECT_EQ(lefts[1].id(), 2288); +} + +TEST_F(TestWithIntersectionCrossingMap, following_lanelets) +{ + const auto following = lanelet2_utility::following_lanelets( + lanelet_map_ptr_->laneletLayer.get(2244), routing_graph_ptr_); + EXPECT_EQ(following.size(), 2); + const auto ids = following | ranges::views::transform([](const auto & l) { return l.id(); }) | + ranges::to(); + EXPECT_EQ(ids.find(2271) != ids.end(), true); + EXPECT_EQ(ids.find(2265) != ids.end(), true); } +/* class TestWithIntersection_T_ShapeMap : public ::testing::Test { protected: @@ -168,6 +186,7 @@ TEST_F(TestWithIntersection_T_ShapeMap, LoadCheck) EXPECT_EQ(point.x(), 0.0); EXPECT_EQ(point.y(), 0.0); } +*/ } // namespace autoware int main(int argc, char ** argv) From 0b12536bfac8cc78b670b943da6e9c5944aead99 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 6 Mar 2025 20:27:31 +0900 Subject: [PATCH 12/17] added more tests Signed-off-by: Mamoru Sobue --- .../autoware_lanelet2_utility/topology.hpp | 2 +- .../intersection/crossing_inverse.osm | 12470 ++++++++++++++++ .../src/topology.cpp | 12 +- .../test/topology.cpp | 89 +- 4 files changed, 12562 insertions(+), 11 deletions(-) create mode 100644 common/autoware_lanelet2_utility/sample_map/intersection/crossing_inverse.osm diff --git a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp index 1ea97b8ac..1fab4540e 100644 --- a/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp +++ b/common/autoware_lanelet2_utility/include/autoware_lanelet2_utility/topology.hpp @@ -167,7 +167,7 @@ lanelet::ConstLanelets previous_lanelets( * @brief get the sibling lanelets * @param [in] lanelet input lanelet * @param [in] routing_graph routing_graph containing `lanelet` - * @return the sibling lanelets + * @return the sibling lanelets excluding `lanelet` */ lanelet::ConstLanelets sibling_lanelets( const lanelet::ConstLanelet & lanelet, diff --git a/common/autoware_lanelet2_utility/sample_map/intersection/crossing_inverse.osm b/common/autoware_lanelet2_utility/sample_map/intersection/crossing_inverse.osm new file mode 100644 index 000000000..17eca88dc --- /dev/null +++ b/common/autoware_lanelet2_utility/sample_map/intersection/crossing_inverse.osm @@ -0,0 +1,12470 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/common/autoware_lanelet2_utility/src/topology.cpp b/common/autoware_lanelet2_utility/src/topology.cpp index 42693ffae..49f8c8216 100644 --- a/common/autoware_lanelet2_utility/src/topology.cpp +++ b/common/autoware_lanelet2_utility/src/topology.cpp @@ -109,10 +109,12 @@ std::optional leftmost_lanelet( bundle_size_diagnosis++; } + // LCOV_EXCL_START RCLCPP_ERROR( rclcpp::get_logger("autoware_lanelet2_utility"), "You have passed an unrealistic map with a bundle of size>=10"); return std::nullopt; + // LCOV_EXCL_STOP } std::optional rightmost_lanelet( @@ -133,10 +135,12 @@ std::optional rightmost_lanelet( bundle_size_diagnosis++; } + // LCOV_EXCL_START RCLCPP_ERROR( rclcpp::get_logger("autoware_lanelet2_utility"), "You have passed an unrealistic map with a bundle of size>=10"); return std::nullopt; + // LCOV_EXCL_STOP } lanelet::ConstLanelets left_lanelets( @@ -155,21 +159,24 @@ lanelet::ConstLanelets left_lanelets( left_lane = left_lanelet(left_lane.value(), routing_graph); bundle_size_diagnosis++; } + // LCOV_EXCL_START if (bundle_size_diagnosis >= k_normal_bundle_max_size) { RCLCPP_ERROR( rclcpp::get_logger("autoware_lanelet2_utility"), "You have passed an unrealistic map with a bundle of size>=10"); return {}; } + // LCOV_EXCL_STOP if (lefts.empty()) { return {}; } const auto & leftmost = lefts.back(); if (include_opposite) { - const auto direct_opposite = right_opposite_lanelet(leftmost, lanelet_map); + const auto direct_opposite = left_opposite_lanelet(leftmost, lanelet_map); if (direct_opposite) { const auto opposites = right_lanelets(direct_opposite.value(), lanelet_map, routing_graph, false, false); + lefts.push_back(direct_opposite.value()); for (const auto & opposite : opposites) { lefts.push_back(invert_opposite_lane ? opposite.invert() : opposite); } @@ -194,12 +201,14 @@ lanelet::ConstLanelets right_lanelets( right_lane = right_lanelet(right_lane.value(), routing_graph); bundle_size_diagnosis++; } + // LCOV_EXCL_START if (bundle_size_diagnosis >= k_normal_bundle_max_size) { RCLCPP_ERROR( rclcpp::get_logger("autoware_lanelet2_utility"), "You have passed an unrealistic map with a bundle of size>=10"); return {}; } + // LCOV_EXCL_STOP if (rights.empty()) { return {}; } @@ -209,6 +218,7 @@ lanelet::ConstLanelets right_lanelets( if (direct_opposite) { const auto opposites = left_lanelets(direct_opposite.value(), lanelet_map, routing_graph, false, false); + rights.push_back(direct_opposite.value()); for (const auto & opposite : opposites) { rights.push_back(invert_opposite_lane ? opposite.invert() : opposite); } diff --git a/common/autoware_lanelet2_utility/test/topology.cpp b/common/autoware_lanelet2_utility/test/topology.cpp index 1e59fcaa1..92486a5e4 100644 --- a/common/autoware_lanelet2_utility/test/topology.cpp +++ b/common/autoware_lanelet2_utility/test/topology.cpp @@ -24,6 +24,7 @@ #include #include #include +#include namespace fs = std::filesystem; @@ -141,6 +142,13 @@ TEST_F(TestWithIntersectionCrossingMap, left_lanelets_without_opposite) EXPECT_EQ(lefts[1].id(), 2286); } +TEST_F(TestWithIntersectionCrossingMap, left_lanelets_without_opposite_empty) +{ + const auto lefts = lanelet2_utility::left_lanelets( + lanelet_map_ptr_->laneletLayer.get(2286), lanelet_map_ptr_, routing_graph_ptr_); + EXPECT_EQ(lefts.size(), 0); +} + TEST_F(TestWithIntersectionCrossingMap, right_lanelets_without_opposite) { const auto lefts = lanelet2_utility::right_lanelets( @@ -150,6 +158,25 @@ TEST_F(TestWithIntersectionCrossingMap, right_lanelets_without_opposite) EXPECT_EQ(lefts[1].id(), 2288); } +TEST_F(TestWithIntersectionCrossingMap, right_lanelets_without_opposite_empty) +{ + const auto lefts = lanelet2_utility::right_lanelets( + lanelet_map_ptr_->laneletLayer.get(2288), lanelet_map_ptr_, routing_graph_ptr_); + EXPECT_EQ(lefts.size(), 0); +} + +TEST_F(TestWithIntersectionCrossingMap, right_lanelets_with_opposite) +{ + const auto rights = lanelet2_utility::right_lanelets( + lanelet_map_ptr_->laneletLayer.get(2286), lanelet_map_ptr_, routing_graph_ptr_, + true /* include opposite */); + EXPECT_EQ(rights.size(), 4); + EXPECT_EQ(rights[0].id(), 2287); + EXPECT_EQ(rights[1].id(), 2288); + EXPECT_EQ(rights[2].id(), 2311); + EXPECT_EQ(rights[3].id(), 2312); +} + TEST_F(TestWithIntersectionCrossingMap, following_lanelets) { const auto following = lanelet2_utility::following_lanelets( @@ -161,8 +188,40 @@ TEST_F(TestWithIntersectionCrossingMap, following_lanelets) EXPECT_EQ(ids.find(2265) != ids.end(), true); } -/* -class TestWithIntersection_T_ShapeMap : public ::testing::Test +TEST_F(TestWithIntersectionCrossingMap, previous_lanelets) +{ + const auto previous = lanelet2_utility::previous_lanelets( + lanelet_map_ptr_->laneletLayer.get(2249), routing_graph_ptr_); + EXPECT_EQ(previous.size(), 3); + const auto ids = previous | ranges::view::transform([](const auto & l) { return l.id(); }) | + ranges::to(); + EXPECT_EQ(ids.find(2283) != ids.end(), true); + EXPECT_EQ(ids.find(2265) != ids.end(), true); + EXPECT_EQ(ids.find(2270) != ids.end(), true); +} + +TEST_F(TestWithIntersectionCrossingMap, sibling_lanelets) +{ + const auto siblings = lanelet2_utility::sibling_lanelets( + lanelet_map_ptr_->laneletLayer.get(2273), routing_graph_ptr_); + const auto ids = siblings | ranges::view::transform([](const auto & l) { return l.id(); }) | + ranges::to(); + EXPECT_EQ(ids.find(2273) != ids.end(), false); + EXPECT_EQ(ids.find(2280) != ids.end(), true); + EXPECT_EQ(ids.find(2281) != ids.end(), true); +} + +TEST_F(TestWithIntersectionCrossingMap, from_ids) +{ + const auto lanelets = + lanelet2_utility::from_ids(lanelet_map_ptr_, std::vector({2296, 2286, 2270})); + EXPECT_EQ(lanelets.size(), 3); + EXPECT_EQ(lanelets[0].id(), 2296); + EXPECT_EQ(lanelets[1].id(), 2286); + EXPECT_EQ(lanelets[2].id(), 2270); +} + +class TestWithIntersectionCrossingInverseMap : public ::testing::Test { protected: lanelet::LaneletMapConstPtr lanelet_map_ptr_{nullptr}; @@ -173,20 +232,32 @@ class TestWithIntersection_T_ShapeMap : public ::testing::Test const auto sample_map_dir = fs::path(ament_index_cpp::get_package_share_directory("autoware_lanelet2_utility")) / "sample_map"; - const auto intersection_t_shape_map_path = sample_map_dir / "intersection" / "T-Shape.osm"; + const auto intersection_crossing_map_path = + sample_map_dir / "intersection" / "crossing_inverse.osm"; - lanelet_map_ptr_ = load_local_coordinate_map(intersection_t_shape_map_path.string()); + lanelet_map_ptr_ = load_mgrs_coordinate_map(intersection_crossing_map_path.string()); routing_graph_ptr_ = lanelet2_utility::instantiate_routing_graph(lanelet_map_ptr_); } }; -TEST_F(TestWithIntersection_T_ShapeMap, LoadCheck) +TEST_F(TestWithIntersectionCrossingInverseMap, left_opposite_lanelet) +{ + const auto lane = lanelet2_utility::left_opposite_lanelet( + lanelet_map_ptr_->laneletLayer.get(2311), lanelet_map_ptr_); + EXPECT_EQ(lane.value().id(), 2288); +} + +TEST_F(TestWithIntersectionCrossingInverseMap, left_lanelets_with_opposite) { - const auto point = lanelet_map_ptr_->pointLayer.get(212); - EXPECT_EQ(point.x(), 0.0); - EXPECT_EQ(point.y(), 0.0); + const auto lefts = lanelet2_utility::left_lanelets( + lanelet_map_ptr_->laneletLayer.get(2312), lanelet_map_ptr_, routing_graph_ptr_, true); + EXPECT_EQ(lefts.size(), 4); + EXPECT_EQ(lefts[0].id(), 2311); + EXPECT_EQ(lefts[1].id(), 2288); + EXPECT_EQ(lefts[2].id(), 2287); + EXPECT_EQ(lefts[3].id(), 2286); } -*/ + } // namespace autoware int main(int argc, char ** argv) From bbff5c6015e8736cdeae29b583e6d2794e91d572 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 6 Mar 2025 20:57:33 +0900 Subject: [PATCH 13/17] added more tests Signed-off-by: Mamoru Sobue --- .../src/topology.cpp | 9 +++-- .../test/topology.cpp | 35 +++++++++++++++++-- 2 files changed, 37 insertions(+), 7 deletions(-) diff --git a/common/autoware_lanelet2_utility/src/topology.cpp b/common/autoware_lanelet2_utility/src/topology.cpp index 49f8c8216..ce50e2832 100644 --- a/common/autoware_lanelet2_utility/src/topology.cpp +++ b/common/autoware_lanelet2_utility/src/topology.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include @@ -256,10 +257,8 @@ lanelet::ConstLanelets sibling_lanelets( lanelet::ConstLanelets from_ids( const lanelet::LaneletMapConstPtr lanelet_map, const std::vector & ids) { - lanelet::ConstLanelets lanelets; - for (const auto id : ids) { - lanelets.push_back(lanelet_map->laneletLayer.get(id)); - } - return lanelets; + return ids | + ranges::view::transform([&](const auto id) { return lanelet_map->laneletLayer.get(id); }) | + ranges::to(); } } // namespace autoware::lanelet2_utility diff --git a/common/autoware_lanelet2_utility/test/topology.cpp b/common/autoware_lanelet2_utility/test/topology.cpp index 92486a5e4..574444f41 100644 --- a/common/autoware_lanelet2_utility/test/topology.cpp +++ b/common/autoware_lanelet2_utility/test/topology.cpp @@ -98,13 +98,20 @@ TEST_F(TestWithIntersectionCrossingMap, right_lanelet_with_lc_permission) EXPECT_EQ(lane.value().id(), 2245); } -TEST_F(TestWithIntersectionCrossingMap, right_opposite_lanelet) +TEST_F(TestWithIntersectionCrossingMap, right_opposite_lanelet_valid) { const auto lane = lanelet2_utility::right_opposite_lanelet( lanelet_map_ptr_->laneletLayer.get(2288), lanelet_map_ptr_); EXPECT_EQ(lane.value().id(), 2311); } +TEST_F(TestWithIntersectionCrossingMap, right_opposite_lanelet_null) +{ + const auto lane = lanelet2_utility::right_opposite_lanelet( + lanelet_map_ptr_->laneletLayer.get(2260), lanelet_map_ptr_); + EXPECT_EQ(lane.has_value(), false); +} + TEST_F(TestWithIntersectionCrossingMap, leftmost_lanelet_valid) { const auto lane = lanelet2_utility::leftmost_lanelet( @@ -177,6 +184,15 @@ TEST_F(TestWithIntersectionCrossingMap, right_lanelets_with_opposite) EXPECT_EQ(rights[3].id(), 2312); } +TEST_F(TestWithIntersectionCrossingMap, right_lanelets_with_opposite_without_actual_opposites) +{ + const auto rights = lanelet2_utility::right_lanelets( + lanelet_map_ptr_->laneletLayer.get(2259), lanelet_map_ptr_, routing_graph_ptr_, + true /* include opposite */); + EXPECT_EQ(rights.size(), 1); + EXPECT_EQ(rights[0].id(), 2260); +} + TEST_F(TestWithIntersectionCrossingMap, following_lanelets) { const auto following = lanelet2_utility::following_lanelets( @@ -240,13 +256,20 @@ class TestWithIntersectionCrossingInverseMap : public ::testing::Test } }; -TEST_F(TestWithIntersectionCrossingInverseMap, left_opposite_lanelet) +TEST_F(TestWithIntersectionCrossingInverseMap, left_opposite_lanelet_valid) { const auto lane = lanelet2_utility::left_opposite_lanelet( lanelet_map_ptr_->laneletLayer.get(2311), lanelet_map_ptr_); EXPECT_EQ(lane.value().id(), 2288); } +TEST_F(TestWithIntersectionCrossingInverseMap, left_opposite_lanelet_null) +{ + const auto lane = lanelet2_utility::left_opposite_lanelet( + lanelet_map_ptr_->laneletLayer.get(2252), lanelet_map_ptr_); + EXPECT_EQ(lane.has_value(), false); +} + TEST_F(TestWithIntersectionCrossingInverseMap, left_lanelets_with_opposite) { const auto lefts = lanelet2_utility::left_lanelets( @@ -258,6 +281,14 @@ TEST_F(TestWithIntersectionCrossingInverseMap, left_lanelets_with_opposite) EXPECT_EQ(lefts[3].id(), 2286); } +TEST_F(TestWithIntersectionCrossingInverseMap, left_lanelets_with_opposite_without_actual_opposites) +{ + const auto lefts = lanelet2_utility::left_lanelets( + lanelet_map_ptr_->laneletLayer.get(2251), lanelet_map_ptr_, routing_graph_ptr_, true); + EXPECT_EQ(lefts.size(), 1); + EXPECT_EQ(lefts[0].id(), 2252); +} + } // namespace autoware int main(int argc, char ** argv) From 26da71e258aa21254706600286f496905fcbf059 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 6 Mar 2025 21:28:30 +0900 Subject: [PATCH 14/17] update docs Signed-off-by: Mamoru Sobue --- common/autoware_lanelet2_utility/README.md | 44 +- .../media/api/left_lanelets.drawio.svg | 987 ++++++++++++++---- .../media/api/right_lanelets.drawio.svg | 687 ++++++++---- 3 files changed, 1296 insertions(+), 422 deletions(-) diff --git a/common/autoware_lanelet2_utility/README.md b/common/autoware_lanelet2_utility/README.md index ede576760..45e8d6b0e 100644 --- a/common/autoware_lanelet2_utility/README.md +++ b/common/autoware_lanelet2_utility/README.md @@ -26,26 +26,26 @@ This package aims to strictly define the meaning of several words to clarify the ## API description -| Header | function | description | average computational complexity | illustration | -| ------------------------------------------ | ----------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `` | `is_road_lane` | | $O(1)$ | | -| | `is_shoulder_lane` | | $O(1)$ | | -| | `is_bicycle_lane` | | $O(1)$ | | -| `` | `instantiate_routing_graph` | This function creates a `RoutingGraph` object only from "road" lanes, which means "road_shoulder" and "bicycle_lane" Lanelets are inaccessible from left/right adjacency. | | | -| | `left_lanelet` | This function ignores the permission of lane change. Also it ignores `shoulder` and `bicycle` Lanelet. | $O(1)$ | In the first map, the green Lanelet is the `left_lanelet` of the orange Lanelet.
In the second and third map, the `left_lanelet` of the orange Lanelet is `null`.
![left_lanelet](./media/api/left_lanelet.drawio.svg) | -| | `right_lanelet` | same as above `left_lanelet` | $O(1)$ | | -| | `left_similar_lanelet`(TODO) | same as above `left_lanelet` | $O(1)$ | | -| | `right_similar_lanelet`(TODO) | same as above `left_lanelet` | $O(1)$ | | -| | `left_opposite_lanelet` | same as below `right_opposite_lanelet` | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | | -| | `right_opposite_lanelet` | | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | In the first and second map, the green Lanelet is the `right_opposite_lanelet` of the orange Lanelet.
In the third map, the `right_opposite_lanelet` of the orange Lanelet is `null`.
![right_opposite_lanelet](./media/api/right_opposite_lanelet.drawio.svg) | -| | `leftmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first and second map, the green Lanelet is the `leftmost_lanelet` of the orange Lanelet.
In the third map, the `leftmost_lanelet` of the orange Lanelet is `null`.
![leftmost_lanelet](./media/api/leftmost_lanelet.drawio.svg) | -| | `rightmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelet is the `rightmost_lanelet` of the orange Lanelet.
In the second and third map, the `rightmost_lanelet` of the orange Lanelet is `null`.
![rightmost_lanelet](./media/api/rightmost_lanelet.drawio.svg) | -| | `left_lanelets` | The input Lanelet is not included in the output. | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelets are the `left_lanelets` of the orange Lanelet.
In the second and third map, `left_lanelets` of the orange Lanelet is empty.
![left_lanelets](./media/api/left_lanelets.drawio.svg) | -| | `right_lanelets` | same as above `left_lanelets`. | $O(W)$ where $W$ is the size of the `bundle.` | In the first map, the green Lanelets are the `right_lanelets` of the orange Lanelet.
In the second and third map, `right_lanelets` of the orange Lanelet is empty.
![right_lanelets](./media/api/right_lanelets.drawio.svg) | -| | `following_lanelets` | | $O(E)$ where $E$ is the number of Lanelets to which the input is connected to. | | -| | `previous_lanelets` | | $O(E)$ where $E$ is the number of Lanelets from which the input is connected from. | | -| | `sibling_lanelets` | | $O(E)$ where $E$ is the number of sibling Lanelets | | -| | `from_ids` | | $O(n)$ | | +| Header | function | description | average computational complexity | illustration | +| ------------------------------------------ | ----------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `` | `is_road_lane` | | $O(1)$ | | +| | `is_shoulder_lane` | | $O(1)$ | | +| | `is_bicycle_lane` | | $O(1)$ | | +| `` | `instantiate_routing_graph` | This function creates a `RoutingGraph` object only from "road" lanes, which means "road_shoulder" and "bicycle_lane" Lanelets are inaccessible from left/right adjacency. | | | +| | `left_lanelet` | This function ignores the permission of lane change. Also it ignores `shoulder` and `bicycle` Lanelet. | $O(1)$ | In the first map, the green Lanelet is the `left_lanelet` of the orange Lanelet.
In the second and third map, the `left_lanelet` of the orange Lanelet is `null`.
![left_lanelet](./media/api/left_lanelet.drawio.svg) | +| | `right_lanelet` | same as above `left_lanelet` | $O(1)$ | | +| | `left_similar_lanelet`(TODO) | same as above `left_lanelet` | $O(1)$ | | +| | `right_similar_lanelet`(TODO) | same as above `left_lanelet` | $O(1)$ | | +| | `left_opposite_lanelet` | same as below `right_opposite_lanelet` | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | | +| | `right_opposite_lanelet` | | $O(1)$
see [`findUsage`](./#complexity-of-findusage) for detail | In the first and second map, the green Lanelet is the `right_opposite_lanelet` of the orange Lanelet.
In the third map, the `right_opposite_lanelet` of the orange Lanelet is `null`.
![right_opposite_lanelet](./media/api/right_opposite_lanelet.drawio.svg) | +| | `leftmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first and second map, the green Lanelet is the `leftmost_lanelet` of the orange Lanelet.
In the third map, the `leftmost_lanelet` of the orange Lanelet is `null`.
![leftmost_lanelet](./media/api/leftmost_lanelet.drawio.svg) | +| | `rightmost_lanelet` | | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelet is the `rightmost_lanelet` of the orange Lanelet.
In the second and third map, the `rightmost_lanelet` of the orange Lanelet is `null`.
![rightmost_lanelet](./media/api/rightmost_lanelet.drawio.svg) | +| | `left_lanelets` | The input Lanelet is not included in the output. | $O(W)$ where $W$ is the size of the `bundle`. | In the first map, the green Lanelets are the `left_lanelets` of the orange Lanelet.
In the second and third map, `left_lanelets` of the orange Lanelet is empty.
If the flag `include_opposite = true`, the left opposite Lanelet and all of its `same_direction` Lanelets area also retrieved as illustrated in the fourth and fifth maps.
![left_lanelets](./media/api/left_lanelets.drawio.svg) | +| | `right_lanelets` | same as above `left_lanelets`. | $O(W)$ where $W$ is the size of the `bundle.` | In the first map, the green Lanelets are the `right_lanelets` of the orange Lanelet.
In the second and third map, `right_lanelets` of the orange Lanelet is empty.
If the flag `include_opposite = true`, the right opposite Lanelet and all of its `same_direction` Lanelets area also retrieved as illustrated in the fourth and fifth maps.
![right_lanelets](./media/api/right_lanelets.drawio.svg) | +| | `following_lanelets` | | $O(E)$ where $E$ is the number of Lanelets to which the input is connected to. | | +| | `previous_lanelets` | | $O(E)$ where $E$ is the number of Lanelets from which the input is connected from. | | +| | `sibling_lanelets` | | $O(E)$ where $E$ is the number of sibling Lanelets | | +| | `from_ids` | | $O(n)$ | | ### complexity of `findUsage` @@ -159,7 +159,7 @@ std::vector forEachMatchInMultiMap(const MapT& map, const KeyT& key, Func&& f ## Test maps -All of the maps are in `local` coordinate. +All of the maps are in `MGRS` coordinate. In each map, an anchor point is set to an origin point $(100.0, 100.0)$ for simplicity. | Map name | Origin point id | Image | | --------------------------- | --------------- | --------------------------------------------------- | @@ -169,7 +169,7 @@ All of the maps are in `local` coordinate. ### How to craft test map -On the VMB, create the map in MGRS system and save the file as ``. Next, select the point to set (100.0, 100.0) and pass its `` and run +On the VMB, create the map in MGRS system and save the file as ``. Next, select the point to set as origin, get its `` and run ```bash ros2 run autoware_lanelet2_utility lanelet_anonymizer.py diff --git a/common/autoware_lanelet2_utility/media/api/left_lanelets.drawio.svg b/common/autoware_lanelet2_utility/media/api/left_lanelets.drawio.svg index 64edd454c..5eac8f02d 100644 --- a/common/autoware_lanelet2_utility/media/api/left_lanelets.drawio.svg +++ b/common/autoware_lanelet2_utility/media/api/left_lanelets.drawio.svg @@ -5,136 +5,142 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="1122px" - height="555px" - viewBox="-0.5 -0.5 1122 555" - content="<mxfile host="Electron" modified="2025-03-02T22:18:46.196Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="hKYweLl4rWbtMYw8dBpX" version="20.3.0" type="device"><diagram id="eq9gud2WWk_s3i5_h-gE" name="Page-1">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</diagram></mxfile>" + width="1129px" + height="1230px" + viewBox="-0.5 -0.5 1129 1230" + content="<mxfile host="Electron" modified="2025-03-06T12:27:02.409Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="HNWBCy4w_KWpEEUisrMr" version="20.3.0" type="device"><diagram id="eq9gud2WWk_s3i5_h-gE" name="Page-1">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</diagram></mxfile>" > - - + + - - + + + + + + + + - - - - - - - - - + + + + + + + + + - + - - - - + + + + - - + + - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + - - + + - + - + - - - - + + + + - + - - + + - - - - - - - - - - - - - - + + + + + + + + + + + + + + - - + + - + - - - - + + + + - - - + + + - - - shoulder lane + + + shoulder lane - - - - - - bicycle lane + + + + + + bicycle lane - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - + - + - - - - - - - + + + + + + + - - - - - + + + + + -

+
2 @@ -589,14 +592,14 @@
- 2 + 2 - + -
+
@@ -606,14 +609,14 @@
- (3) + (3) - + -
+
@@ -623,14 +626,14 @@
- (1) + (1) - + -
+
@@ -640,17 +643,17 @@
- (2) + (2) - - - + + +
@@ -659,7 +662,545 @@
- 1 + 1 + + + + + + +
+
+
+ + include_opposite = false (default) + +
+
+
+
+ include_opposite = false (default) +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + shoulder lane + + + + + + + bicycle lane + + + + + +
+
+
+ + (5) + +
+
+
+
+ (5) +
+
+ + + + +
+
+
+ + (4) + +
+
+
+
+ (4) +
+
+ + + + + +
+
+
+ + include_opposite = true + +
+
+
+
+ include_opposite = true
diff --git a/common/autoware_lanelet2_utility/media/api/right_lanelets.drawio.svg b/common/autoware_lanelet2_utility/media/api/right_lanelets.drawio.svg index 9d6b78f37..318269020 100644 --- a/common/autoware_lanelet2_utility/media/api/right_lanelets.drawio.svg +++ b/common/autoware_lanelet2_utility/media/api/right_lanelets.drawio.svg @@ -5,106 +5,109 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="1052px" - height="546px" - viewBox="-0.5 -0.5 1052 546" - content="<mxfile host="Electron" modified="2025-03-02T22:18:28.567Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="cTGvevZYgQ9GiPV8-lAk" version="20.3.0" type="device"><diagram id="eq9gud2WWk_s3i5_h-gE" name="Page-1">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</diagram></mxfile>" + width="1059px" + height="1262px" + viewBox="-0.5 -0.5 1059 1262" + content="<mxfile host="Electron" modified="2025-03-06T12:27:19.976Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="qIXNYzKJ7irkuYJZfdFw" version="20.3.0" type="device"><diagram id="eq9gud2WWk_s3i5_h-gE" name="Page-1">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</diagram></mxfile>" > - - + + + + + - - - + + + - - + + - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + - - + + - + - + - - - - + + + + - - - - - - bicycle lane + + + + + + bicycle lane - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - + - + - - - - - - - + + + + + + + - - - - - + + + + +
@@ -308,14 +311,14 @@
- 2 + 2 - + -
+
@@ -325,14 +328,14 @@
- (1) + (1) - + -
+
@@ -342,94 +345,94 @@
- (2) + (2) - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - + - + - - - - - - - + + + + + + + - - - + + + -
+
@@ -439,16 +442,16 @@
- (3) + (3) - - + +
@@ -457,7 +460,337 @@
- 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + shoulder lane + + + + + +
+
+
+ + (4) + +
+
+
+
+ (4) +
+
+ + + + + +
+
+
+ + include_opposite = false (default) + +
+
+
+
+ include_opposite = false (default) +
+
+ + + + +
+
+
+ + include_opposite = true + +
+
+
+
+ include_opposite = true
From 345fc84122f1c20d8959290b4053dae1e7daacf9 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 6 Mar 2025 21:47:50 +0900 Subject: [PATCH 15/17] fix Signed-off-by: Mamoru Sobue --- .../intersection/crossing_fms_original.osm | 14533 ---------------- .../sample_map/road_shoulder/fms.osm | 3464 ---- .../src/topology.cpp | 5 +- .../test/topology.cpp | 4 +- 4 files changed, 5 insertions(+), 18001 deletions(-) delete mode 100644 common/autoware_lanelet2_utility/sample_map/intersection/crossing_fms_original.osm delete mode 100644 common/autoware_lanelet2_utility/sample_map/road_shoulder/fms.osm diff --git a/common/autoware_lanelet2_utility/sample_map/intersection/crossing_fms_original.osm b/common/autoware_lanelet2_utility/sample_map/intersection/crossing_fms_original.osm deleted file mode 100644 index f91599594..000000000 --- a/common/autoware_lanelet2_utility/sample_map/intersection/crossing_fms_original.osm +++ /dev/null @@ -1,14533 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/common/autoware_lanelet2_utility/sample_map/road_shoulder/fms.osm b/common/autoware_lanelet2_utility/sample_map/road_shoulder/fms.osm deleted file mode 100644 index 3c652586d..000000000 --- a/common/autoware_lanelet2_utility/sample_map/road_shoulder/fms.osm +++ /dev/null @@ -1,3464 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/common/autoware_lanelet2_utility/src/topology.cpp b/common/autoware_lanelet2_utility/src/topology.cpp index ce50e2832..164b1e118 100644 --- a/common/autoware_lanelet2_utility/src/topology.cpp +++ b/common/autoware_lanelet2_utility/src/topology.cpp @@ -257,8 +257,9 @@ lanelet::ConstLanelets sibling_lanelets( lanelet::ConstLanelets from_ids( const lanelet::LaneletMapConstPtr lanelet_map, const std::vector & ids) { - return ids | - ranges::view::transform([&](const auto id) { return lanelet_map->laneletLayer.get(id); }) | + return ids | ranges::views::transform([&](const auto id) { + return lanelet_map->laneletLayer.get(id); + }) | ranges::to(); } } // namespace autoware::lanelet2_utility diff --git a/common/autoware_lanelet2_utility/test/topology.cpp b/common/autoware_lanelet2_utility/test/topology.cpp index 574444f41..0f57bb876 100644 --- a/common/autoware_lanelet2_utility/test/topology.cpp +++ b/common/autoware_lanelet2_utility/test/topology.cpp @@ -209,7 +209,7 @@ TEST_F(TestWithIntersectionCrossingMap, previous_lanelets) const auto previous = lanelet2_utility::previous_lanelets( lanelet_map_ptr_->laneletLayer.get(2249), routing_graph_ptr_); EXPECT_EQ(previous.size(), 3); - const auto ids = previous | ranges::view::transform([](const auto & l) { return l.id(); }) | + const auto ids = previous | ranges::views::transform([](const auto & l) { return l.id(); }) | ranges::to(); EXPECT_EQ(ids.find(2283) != ids.end(), true); EXPECT_EQ(ids.find(2265) != ids.end(), true); @@ -220,7 +220,7 @@ TEST_F(TestWithIntersectionCrossingMap, sibling_lanelets) { const auto siblings = lanelet2_utility::sibling_lanelets( lanelet_map_ptr_->laneletLayer.get(2273), routing_graph_ptr_); - const auto ids = siblings | ranges::view::transform([](const auto & l) { return l.id(); }) | + const auto ids = siblings | ranges::views::transform([](const auto & l) { return l.id(); }) | ranges::to(); EXPECT_EQ(ids.find(2273) != ids.end(), false); EXPECT_EQ(ids.find(2280) != ids.end(), true); From 938ed96de5877689f8db47378efb6e895ea6c94f Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 6 Mar 2025 21:51:29 +0900 Subject: [PATCH 16/17] fix2 Signed-off-by: Mamoru Sobue --- common/autoware_lanelet2_utility/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/common/autoware_lanelet2_utility/package.xml b/common/autoware_lanelet2_utility/package.xml index d526dbeea..c2207bbfa 100644 --- a/common/autoware_lanelet2_utility/package.xml +++ b/common/autoware_lanelet2_utility/package.xml @@ -15,7 +15,6 @@ autoware_lanelet2_extension range-v3 rclcpp - visualization_msgs ament_cmake_ros ament_index_cpp From 5c2aa46e0ce25bc6ec8feafce2730cfdbaf64de3 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 7 Mar 2025 11:04:28 +0900 Subject: [PATCH 17/17] add maintainer Signed-off-by: Mamoru Sobue --- common/autoware_lanelet2_utility/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/common/autoware_lanelet2_utility/package.xml b/common/autoware_lanelet2_utility/package.xml index c2207bbfa..38d3e7b2e 100644 --- a/common/autoware_lanelet2_utility/package.xml +++ b/common/autoware_lanelet2_utility/package.xml @@ -5,6 +5,7 @@ 0.0.0 The autoware_lanelet2_utility package Mamoru Sobue + Kosuke Takeuchi Apache License 2.0 Mamoru Sobue