From 57c238cbdb84dd1702f7d8989d27ea738d068b21 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Fri, 26 Apr 2024 18:47:19 +0900 Subject: [PATCH] feat(ndt_scan_matcher): remake diag (#5076) * feat(ndt_scan_matcher): remake diag Signed-off-by: yamato-ando * style(pre-commit): autofix * add latest_ndt_aling_service_best_score Signed-off-by: yamato-ando * style(pre-commit): autofix * check nullptr Signed-off-by: yamato-ando * style(pre-commit): autofix * add validate_distance_from_initial_to_result Signed-off-by: yamato-ando * style(pre-commit): autofix * rename Signed-off-by: yamato-ando * style(pre-commit): autofix * style(pre-commit): autofix * [WIP] update Signed-off-by: Yamato Ando * style(pre-commit): autofix * [WIP] update Signed-off-by: Yamato Ando * [WIP] update Signed-off-by: Yamato Ando * style(pre-commit): autofix * [WIP] update Signed-off-by: Yamato Ando * fix typo Signed-off-by: Yamato Ando * style(pre-commit): autofix * [WIP] update Signed-off-by: Yamato Ando * style(pre-commit): autofix * update readme Signed-off-by: Yamato Ando * style(pre-commit): autofix * [WIP] update Signed-off-by: Yamato Ando * style(pre-commit): autofix * [WIP] update Signed-off-by: Yamato Ando * fix typo Signed-off-by: Yamato Ando * style(pre-commit): autofix * [WIP] update Signed-off-by: Yamato Ando * [WIP] udpate Signed-off-by: Yamato Ando * [WIP] udpate Signed-off-by: Yamato Ando * style(pre-commit): autofix * add is_need_rebuild Signed-off-by: Yamato Ando * fix typo Signed-off-by: Yamato Ando * style(pre-commit): autofix * add image Signed-off-by: Yamato Ando * style(pre-commit): autofix * remove unused func Signed-off-by: Yamato Ando * fix Signed-off-by: Yamato Ando * fix typo Signed-off-by: Yamato Ando * style(pre-commit): autofix * update image Signed-off-by: Yamato Ando * fix typo Signed-off-by: Yamato Ando * fix Signed-off-by: Yamato Ando * remove unused include Signed-off-by: Yamato Ando * move code Signed-off-by: Yamato Ando * move code Signed-off-by: Yamato Ando * style(pre-commit): autofix * fix FIX ME Signed-off-by: Yamato Ando * update Signed-off-by: Yamato Ando * remove unused func Signed-off-by: Yamato Ando * [WIP] update Signed-off-by: Yamato Ando * add diag for trigger node service Signed-off-by: Yamato Ando * style(pre-commit): autofix * move code Signed-off-by: Yamato Ando * update Signed-off-by: Yamato Ando * delete unused code Signed-off-by: Yamato Ando * style(pre-commit): autofix * udpate Signed-off-by: Yamato Ando * delete RCLCPP message Signed-off-by: Yamato Ando * style(pre-commit): autofix * update Signed-off-by: Yamato Ando * fix typo Signed-off-by: Yamato Ando * style(pre-commit): autofix * rename diag Signed-off-by: Yamato Ando * rename func Signed-off-by: Yamato Ando * style(pre-commit): autofix * remove Transition condition to OK Signed-off-by: Yamato Ando * style(pre-commit): autofix * fix table Signed-off-by: Yamato Ando * update readme Signed-off-by: Yamato Ando * style(pre-commit): autofix * fix order Signed-off-by: Yamato Ando * fix typo Signed-off-by: Yamato Ando * remove diag prefix Signed-off-by: Yamato Ando * style(pre-commit): autofix * fix readme Signed-off-by: Yamato Ando * style(pre-commit): autofix * rename diag Signed-off-by: Yamato Ando * style(pre-commit): autofix * remove unused code Signed-off-by: Yamato Ando * fix double free Signed-off-by: Yamato Ando * style(pre-commit): autofix * fix typo Signed-off-by: Yamato Ando * output to terminal Signed-off-by: Yamato Ando * style(pre-commit): autofix * fix typo Signed-off-by: Yamato Ando --------- Signed-off-by: yamato-ando Signed-off-by: Yamato Ando Co-authored-by: yamato-ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/ndt_scan_matcher/CMakeLists.txt | 19 +- localization/ndt_scan_matcher/README.md | 100 ++++ .../ndt_scan_matcher/diagnostics_module.hpp | 59 ++ .../ndt_scan_matcher/hyper_parameters.hpp | 10 +- .../ndt_scan_matcher/map_update_module.hpp | 17 +- .../ndt_scan_matcher_core.hpp | 46 +- ...gnostic_initial_pose_subscriber_status.png | Bin 0 -> 23531 bytes .../media/diagnostic_map_update_status.png | Bin 0 -> 61766 bytes .../diagnostic_ndt_align_service_status.png | Bin 0 -> 65598 bytes ..._regularization_pose_subscriber_status.png | Bin 0 -> 17947 bytes .../media/diagnostic_scan_matching_status.png | Bin 0 -> 74021 bytes ...diagnostic_trigger_node_service_status.png | Bin 0 -> 24741 bytes .../src/diagnostics_module.cpp | 104 ++++ .../src/map_update_module.cpp | 112 +++- .../src/ndt_scan_matcher_core.cpp | 543 ++++++++++-------- 15 files changed, 734 insertions(+), 276 deletions(-) create mode 100644 localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp create mode 100644 localization/ndt_scan_matcher/media/diagnostic_initial_pose_subscriber_status.png create mode 100644 localization/ndt_scan_matcher/media/diagnostic_map_update_status.png create mode 100644 localization/ndt_scan_matcher/media/diagnostic_ndt_align_service_status.png create mode 100644 localization/ndt_scan_matcher/media/diagnostic_regularization_pose_subscriber_status.png create mode 100644 localization/ndt_scan_matcher/media/diagnostic_scan_matching_status.png create mode 100644 localization/ndt_scan_matcher/media/diagnostic_trigger_node_service_status.png create mode 100644 localization/ndt_scan_matcher/src/diagnostics_module.cpp diff --git a/localization/ndt_scan_matcher/CMakeLists.txt b/localization/ndt_scan_matcher/CMakeLists.txt index 4806838cf0103..7ac78514c49fe 100644 --- a/localization/ndt_scan_matcher/CMakeLists.txt +++ b/localization/ndt_scan_matcher/CMakeLists.txt @@ -27,10 +27,11 @@ find_package(PCL REQUIRED COMPONENTS common io registration) include_directories(${PCL_INCLUDE_DIRS}) ament_auto_add_executable(ndt_scan_matcher - src/particle.cpp - src/ndt_scan_matcher_node.cpp - src/ndt_scan_matcher_core.cpp + src/diagnostics_module.cpp src/map_update_module.cpp + src/ndt_scan_matcher_core.cpp + src/ndt_scan_matcher_node.cpp + src/particle.cpp ) link_directories(${PCL_LIBRARY_DIRS}) @@ -45,15 +46,19 @@ if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) ament_auto_add_gtest(standard_sequence_for_initial_pose_estimation test/test_cases/standard_sequence_for_initial_pose_estimation.cpp - src/particle.cpp - src/ndt_scan_matcher_core.cpp + src/diagnostics_module.cpp src/map_update_module.cpp + src/ndt_scan_matcher_core.cpp +# src/ndt_scan_matcher_node.cpp + src/particle.cpp ) ament_auto_add_gtest(once_initialize_at_out_of_map_then_initialize_correctly test/test_cases/once_initialize_at_out_of_map_then_initialize_correctly.cpp - src/particle.cpp - src/ndt_scan_matcher_core.cpp + src/diagnostics_module.cpp src/map_update_module.cpp + src/ndt_scan_matcher_core.cpp +# src/ndt_scan_matcher_node.cpp + src/particle.cpp ) endif() diff --git a/localization/ndt_scan_matcher/README.md b/localization/ndt_scan_matcher/README.md index 424a7051de883..fbc2fa3c9a3f3 100644 --- a/localization/ndt_scan_matcher/README.md +++ b/localization/ndt_scan_matcher/README.md @@ -255,3 +255,103 @@ initial_pose_offset_model is rotated around (x,y) = (0,0) in the direction of th initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements. {{ json_to_markdown("localization/ndt_scan_matcher/schema/sub/covariance_covariance_estimation.json") }} + +## Diagnostics + +### scan_matching_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | Whether to reject the estimation result (affects `skipping_publish_num`) | +| ----------------------------------------- | -------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -------------------------------- | ------------------------------------------------------------------------ | +| `topic_time_stamp` | the time stamp of input topic | none | none | no | +| `sensor_points_size` | the size of sensor points | the size is 0 | none | yes | +| `sensor_points_delay_time_sec` | the delay time of sensor points | the time is **longer** than `validation.lidar_topic_timeout_sec` | none | yes | +| `is_succeed_transform_sensor_points` | whether transform sensor points is succeed or not | none | failed | yes | +| `sensor_points_max_distance` | the max distance of sensor points | the max distance is **shorter** than `sensor_points.required_distance` | none | yes | +| `is_activated` | whether the node is in the "activate" state or not | not "activate" state | none | yes | +| `is_succeed_interpolate_initial_pose` | whether the interpolate of initial pose is succeed or not | failed.
(1) the size of `initial_pose_buffer_` is **smaller** than 2.
(2) the timestamp difference between initial_pose and sensor pointcloud is **longer** than `validation.initial_pose_timeout_sec`.
(3) distance difference between two initial poses used for linear interpolation is **longer** than `validation.initial_pose_distance_tolerance_m` | none | yes | +| `is_set_map_points` | whether the map points is set or not | not set | none | yes | +| `iteration_num` | the number of times calculate alignment | the number of times is **larger** than `ndt.max_iterations` | none | yes | +| `local_optimal_solution_oscillation_num` | the number of times the solution is judged to be oscillating | the number of times is **larger** than 10 | none | yes | +| `transform_probability` | the score of how well the map aligns with the sensor points | the score is **smaller** than`score_estimation.converged_param_transform_probability` (only in the case of `score_estimation.converged_param_type` is 0=TRANSFORM_PROBABILITY) | none | yes | +| `nearest_voxel_transformation_likelihood` | the score of how well the map aligns with the sensor points | the score is **smaller** than `score_estimation.converged_param_nearest_voxel_transformation_likelihood` (only in the case of `score_estimation.converged_param_type` is 1=NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD) | none | yes | +| `distance_initial_to_result` | the distance between the position before convergence processing and the position after | the distance is **longer** than 3 | none | no | +| `execution_time` | the time for convergence processing | the time is **longer** than `validation.critical_upper_bound_exe_time_ms` | none | no | +| `skipping_publish_num` | the number of times rejected estimation results consecutively | none | the number of times is 5 or more | - | + +※The `sensor_points_callback` shares the same callback group as the `trigger_node_service` and `ndt_align_service`. Consequently, if the initial pose estimation takes too long, this diagnostic may become stale. + +### initial_pose_subscriber_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | +| ---------------------- | ------------------------------------------------------------------ | ------------------------------- | ----------------------------- | +| `topic_time_stamp` | the time stamp of input topic | none | none | +| `is_activated` | whether the node is in the "activate" state or not | not "activate" state | none | +| `is_expected_frame_id` | whether the input frame_id is the same as `frame.map_frame` or not | none | not the same | + +### regularization_pose_subscriber_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | +| ------------------ | ----------------------------- | ------------------------------- | ----------------------------- | +| `topic_time_stamp` | the time stamp of input topic | none | none | + +### trigger_node_service_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | +| ------------------------- | -------------------------------------------------- | ------------------------------- | ----------------------------- | +| `service_call_time_stamp` | the time stamp of service calling | none | none | +| `is_activated` | whether the node is in the "activate" state or not | none | none | +| `is_succeed_service` | whether the process of service is succeed or not | none | none | + +※ +This diagnostic is only published when the service is called, so it becomes stale after the initial pose estimation is completed. + +### ndt_align_service_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | +| ----------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------- | ----------------------------------------------------------- | +| `service_call_time_stamp` | the time stamp of service calling | none | none | +| `is_succeed_transform_initial_pose` | whether transform initial pose is succeed or not | none | failed | +| `is_need_rebuild` | whether it need to rebuild the map. If the map has not been loaded yet or if `distance_last_update_position_to_current_position encounters` is an Error state, it is considered necessary to reconstruct the map, and `is_need_rebuild` becomes `True`. | none | none | +| `maps_size_before` | the number of maps before update map | none | none | +| `is_succeed_call_pcd_loader` | whether call pcd_loader service is succeed or not | failed | none | +| `maps_to_add_size` | the number of maps to be added | none | none | +| `maps_to_remove_size` | the number of maps to be removed | none | none | +| `map_update_execution_time` | the time for map updating | none | none | +| `maps_size_after` | the number of maps after update map | none | none | +| `is_updated_map` | whether map is updated. If the map update couldn't be performed or there was no need to update the map, it becomes `False` | none | `is_updated_map` is `False` but `is_need_rebuild` is `True` | +| `is_set_map_points` | whether the map points is set or not | not set | none | +| `is_set_sensor_points` | whether the sensor points is set or not | not set | none | +| `best_particle_score` | the best score of particle | none | none | +| `is_succeed_service` | whether the process of service is succeed or not | failed | none | + +※ +This diagnostic is only published when the service is called, so it becomes stale after the initial pose estimation is completed. + +### map_update_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | +| --------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------- | ------------------------------------------------------------------------------------------------------- | +| `timer_callback_time_stamp` | the time stamp of timer_callback calling | none | none | +| `is_activated` | whether the node is in the "activate" state or not | not "activate" state | none | +| `is_set_last_update_position` | whether the `last_update_position` is set or not | not set | none | +| `distance_last_update_position_to_current_position` | the distance of `last_update_position` to current position | none | (the distance + `dynamic_map_loading.lidar_radius`) is **larger** than `dynamic_map_loading.map_radius` | +| `is_need_rebuild` | whether it need to rebuild the map. If the map has not been loaded yet or if `distance_last_update_position_to_current_position encounters` is an Error state, it is considered necessary to reconstruct the map, and `is_need_rebuild` becomes `True`. | none | none | +| `maps_size_before` | the number of maps before update map | none | none | +| `is_succeed_call_pcd_loader` | whether call pcd_loader service is succeed or not | failed | none | +| `maps_to_add_size` | the number of maps to be added | none | none | +| `maps_to_remove_size` | the number of maps to be removed | none | none | +| `map_update_execution_time` | the time for map updating | none | none | +| `maps_size_after` | the number of maps after update map | none | none | +| `is_updated_map` | whether map is updated. If the map update couldn't be performed or there was no need to update the map, it becomes `False` | none | `is_updated_map` is `False` but `is_need_rebuild` is `True` | diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp new file mode 100644 index 0000000000000..828eb6bed346b --- /dev/null +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp @@ -0,0 +1,59 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NDT_SCAN_MATCHER__DIAGNOSTICS_MODULE_HPP_ +#define NDT_SCAN_MATCHER__DIAGNOSTICS_MODULE_HPP_ + +#include + +#include + +#include +#include + +class DiagnosticsModule +{ +public: + DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name); + void clear(); + void addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg); + template + void addKeyValue(const std::string & key, const T & value); + void updateLevelAndMessage(const int8_t level, const std::string & message); + void publish(); + +private: + diagnostic_msgs::msg::DiagnosticArray createDiagnosticsArray() const; + + rclcpp::Clock::SharedPtr clock_; + rclcpp::Publisher::SharedPtr diagnostics_pub_; + + diagnostic_msgs::msg::DiagnosticStatus diagnostics_status_msg_; +}; + +template +void DiagnosticsModule::addKeyValue(const std::string & key, const T & value) +{ + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = key; + key_value.value = std::to_string(value); + addKeyValue(key_value); +} + +template <> +void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value); +template <> +void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value); + +#endif // NDT_SCAN_MATCHER__DIAGNOSTICS_MODULE_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp index ee1e2369c79bd..bc7bf1fe40d36 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -162,10 +163,11 @@ struct HyperParameters initial_pose_offset_model_y[i]; } } else { - RCLCPP_WARN( - node->get_logger(), - "Invalid initial pose offset model parameters. Disable covariance estimation."); - covariance.covariance_estimation.enable = false; + std::stringstream message; + message << "Invalid initial pose offset model parameters." + << "Please make sure that the number of elements in " + << "initial_pose_offset_model_x and initial_pose_offset_model_y are the same."; + throw std::runtime_error(message.str()); } } diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp index 04c762ae950a4..2bcb6f4cf6fb8 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp @@ -16,6 +16,7 @@ #define NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_ #include "localization_util/util_func.hpp" +#include "ndt_scan_matcher/diagnostics_module.hpp" #include "ndt_scan_matcher/hyper_parameters.hpp" #include "ndt_scan_matcher/particle.hpp" @@ -54,10 +55,20 @@ class MapUpdateModule private: friend class NDTScanMatcher; + void callback_timer( + const bool is_activated, const std::optional & position, + std::unique_ptr & diagnostics_ptr); + + [[nodiscard]] bool should_update_map( + const geometry_msgs::msg::Point & position, + std::unique_ptr & diagnostics_ptr); + void update_map( + const geometry_msgs::msg::Point & position, + std::unique_ptr & diagnostics_ptr); // Update the specified NDT - bool update_ndt(const geometry_msgs::msg::Point & position, NdtType & ndt); - void update_map(const geometry_msgs::msg::Point & position); - [[nodiscard]] bool should_update_map(const geometry_msgs::msg::Point & position); + bool update_ndt( + const geometry_msgs::msg::Point & position, NdtType & ndt, + std::unique_ptr & diagnostics_ptr); void publish_partial_pcd_map(); rclcpp::Publisher::SharedPtr loaded_pcd_pub_; diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index 26c96ce7e3248..4f8042d106c75 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -18,6 +18,7 @@ #define FMT_HEADER_ONLY #include "localization_util/smart_pose_buffer.hpp" +#include "ndt_scan_matcher/diagnostics_module.hpp" #include "ndt_scan_matcher/hyper_parameters.hpp" #include "ndt_scan_matcher/map_update_module.hpp" @@ -62,6 +63,7 @@ #include #include #include +#include #include #include #include @@ -77,21 +79,32 @@ class NDTScanMatcher : public rclcpp::Node explicit NDTScanMatcher(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); private: - void service_ndt_align( - const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, - tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res); - void service_trigger_node( - const std_srvs::srv::SetBool::Request::SharedPtr req, - std_srvs::srv::SetBool::Response::SharedPtr res); - void callback_timer(); - void callback_sensor_points( - sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame); + void callback_initial_pose( geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr); + void callback_initial_pose_main( + const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr); + void callback_regularization_pose( geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose_conv_msg_ptr); + void callback_sensor_points( + sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame); + bool callback_sensor_points_main( + sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame); + + void service_trigger_node( + const std_srvs::srv::SetBool::Request::SharedPtr req, + std_srvs::srv::SetBool::Response::SharedPtr res); + + void service_ndt_align( + const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, + tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res); + void service_ndt_align_main( + const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, + tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res); + geometry_msgs::msg::PoseWithCovarianceStamped align_pose( const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_with_cov); @@ -116,11 +129,6 @@ class NDTScanMatcher : public rclcpp::Node const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_old_msg, const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_new_msg); - bool validate_num_iteration(const int iter_num, const int max_iter_num); - bool validate_score( - const double score, const double score_threshold, const std::string & score_name); - bool validate_converged_param( - const double & transform_probability, const double & nearest_voxel_transformation_likelihood); static int count_oscillation(const std::vector & result_pose_msg_array); std::array rotate_covariance( @@ -131,8 +139,6 @@ class NDTScanMatcher : public rclcpp::Node void add_regularization_pose(const rclcpp::Time & sensor_ros_time); - void publish_diagnostic(); - rclcpp::TimerBase::SharedPtr map_update_timer_; rclcpp::Subscription::SharedPtr initial_pose_sub_; rclcpp::Subscription::SharedPtr sensor_points_sub_; @@ -168,7 +174,6 @@ class NDTScanMatcher : public rclcpp::Node rclcpp::Publisher::SharedPtr ndt_marker_pub_; rclcpp::Publisher::SharedPtr ndt_monte_carlo_initial_pose_marker_pub_; - rclcpp::Publisher::SharedPtr diagnostics_pub_; rclcpp::Service::SharedPtr service_; rclcpp::Service::SharedPtr service_trigger_node_; @@ -180,7 +185,6 @@ class NDTScanMatcher : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr timer_callback_group_; std::shared_ptr ndt_ptr_; - std::shared_ptr> state_ptr_; Eigen::Matrix4f base_to_sensor_matrix_; @@ -194,6 +198,12 @@ class NDTScanMatcher : public rclcpp::Node std::unique_ptr regularization_pose_buffer_; std::atomic is_activated_; + std::unique_ptr diagnostics_scan_points_; + std::unique_ptr diagnostics_initial_pose_; + std::unique_ptr diagnostics_regularization_pose_; + std::unique_ptr diagnostics_map_update_; + std::unique_ptr diagnostics_ndt_align_; + std::unique_ptr diagnostics_trigger_node_; std::unique_ptr map_update_module_; std::unique_ptr logger_configure_; diff --git a/localization/ndt_scan_matcher/media/diagnostic_initial_pose_subscriber_status.png b/localization/ndt_scan_matcher/media/diagnostic_initial_pose_subscriber_status.png new file mode 100644 index 0000000000000000000000000000000000000000..766888359ed8e705963214e26a1d48ff3a171d16 GIT binary patch literal 23531 zcmdqJ^;aBGw=D_@At8j|?(Xg$2=49@+}&M+yEX0_ydk&*ch^RPG|;#^%_ZMB=Z!Po zyYK!1w|=NvwMW$+qqeR!=Uf%3q#%j(8SgU;3=ERAl$Z((4D9urUGxe5?d(f;?DTel za}kwR`}B7Belm@CyT^4E*K$>LFn9GZayEmpuy?RCV{|cbHZ!w#v2<`fd*3be_7J<3 znwIN#XEP&LD+hZLH7h%_w?Y^gHWoGxaBCwA$6j^>8^<1?goKrMFC&l5k>mX1D$g635 zeMU@72}4{N1N_R_C!7QOW{E4G=6pVgDx`^0fhiBHp?R}D1paRdUZ)PI0c?j8ThGoq zuVoD?B&~6be?yjp%pni2+wsDB1TPiBIX;Rz2LYX4BW6u<{^3EJCxZ|1rr)UTZ}z|7 zJ+co$kK77&vpyf(1?49FxmaK2&Ah(*2)n=K6+^(8d=mNYlXUnJ@W+5q4fI488bEWx zunK_o4zfR-q3VC!W3yiKy)}3-gm)!{mQmAUX=QEkUt$aCNm5O76r(Uw6G?v5!@dI= zZ|KDFxfn8e@L4QQ8Bewq={+&$PMK0+Yq2}Qp)X}mO17>8kTz!ET@@H`$A-_iT`mmK zr_Y+YTPGvsqqTuAWUn{oHy&fW`P9VVCFM>_?IH@1T#a!JhtB}7gj>JC259iFw5*yJ zv9dszUizl}E5X+zmj{kTBpdngyR^jfTHb?KK|SiyE738F``Z8m=75}qZXV^C5}Mr# zu#MLQV|qk6jSO6S0jVAo?3U?a3$V!~~VkBa_wiL)QM=bl(BI~{_%gKg+?#gQe19Y|3v2`9H&Y78`1OJPeRmgL# z(I>mUmIXUDD8S{Z-H#W%c{Is&ekP2d4)p^X6v(1=cWvaLW-*a2CN&bX#!rM#IbA$U z-`3;|U>kNQAiiF+52uh{c{ZCM_4=J?35wFJ-ir^uImtnqN-Xl>nX8 zB=OWD3oYxIPqEnDUq2BYTq4*^ZaPIB^7WP>YfWq~5!@PH=&5tkcT)W7Bff-Ma4n}&U0{>QUM&RV7M z@&YToCdqEfT6`MsH3#2wE%n}xYOS?rT8#%Q|CR^2jR8<9`GF4gy8v$dQ|Lg&#i23U z2fg;8*^11h>jNF-_Hm_>AHhLLoBDq=%R7Ag+1mq-Z=KNiMBE{z3mtM(@C- zwYBoN#X*l99KH}2Fw!Q#X-|&8?ZK4Mx!Eb!SN?5{L8C*o(DJ-Tf`GfLt1Sys%T*>y zs%Y!(AUf8#cO_VJygKC7T7+bpBL9rGVTmK2pM`msKg;3oMc3?x+L{(WInw&xQn?6& z)PQSTgSj^|pr=59DcR+W7#!(uT7++nrU$8iQ z*Y>zydk7mY zLjM|lHTkaNI;XKQqvViYcsL1@-gHEvp|EmtEjCgG}lJZI+loE&{AaP4+J8{t#4#wBgCihoo4b z-I&gU*$NpbD-C**`ul})@RZ4n&yQvfyE>uds%&i6Y^a}>>~Wx)EnpE%yK@U!o82MB zHKsAjVlEN_{>w*3PFxqI8RD_KUqWv-PuXmqS^=gvC@OX(^abTZ( zNPLP}7Qut;$G}+)JG)hB_n)u${gj{G$y7Krl}t3ixUGAGi~BNH3w&PUWdlF`cAlh6 zYHKNjOYbXLmlPh|PNfF}BAI0w4U;katqb%Nghh8}F9F3Voe3Ox9Qqp2dWAi|H3b>1 zmy(5)x$Pu;E3r}Z9jxI|&PvmnY&Wzc9?DHO8Zx1hr{PO_Z4Y5LCq;z1#YAOEeX{KY zc?Yq`5+(cx(;jE-R^K2w@1laxblxi$oPX@@)q4oS!Npav4{O8y(lO=EK4Y?Bz_S#eczdL7Nwe9`O~;B! zlr64`y1=u|$k--BD$)^P_?`&dzrF*Dn_-bP3trpB+6HS#=jL^&a5=0}RPOmR)5q~T zqynm|$6LHjyvmM=4fLyi8YEy=aIX}JGi=3=;^)26M5j#xB5OGll#=5Gp1mF~js?!^ z=YdZ$>q`MCoVv{;#A5+TdH%xmOsJ?!P7h7u3F+Str8g0T$AI8yaG8VoNZJ^0BeLeL z-Je|p2_pQ<-{S^AwY?Z0gI`Y>#Y$xv&KgsS52lSp(^!{1Q}m`2hlXa8qwjfdArR-< z`0U3ly{E87q*>uvGRnLx+EtH}B>i^xvBawi+<;~oP;=9UKrW?Om+M87%!?ECK&s8# zIxvDZO^E+diWWV%KH~b3kuiK>b~hec(jQ8-H`{3j`T!Wd5o9|wB4*8x^jL*Bi*#eE zO>hb&y;soR?s8y;!izO2ber zQt&Cvg5EHtcX9Q7+wW7HNH?%cyLX50+&ooNxWvd7e?w(nvh;-DfQC&d zfum`=I~7yp%Q0y^{B?>rH~+UvIH6846$kr6U8_Cw)W^KMB!LFN#G___zo>8ZZ?oMk zd>iUvkLtDlmA{C*)fRwZvy7QVeOty-nZmVC2c(zBv-5IeJm5bOnZ`HvOq;nQnZqYJ zzlLL*?3td8y(Me&(wOnvqYcA}cei5~ZlW*s={@SXUnI6~j%SB;-E&%hUuOXyBm{Yo zMM@cY9cV$WnMX>qS(<{#PwpsS2zP@>7>So~5HA4Lt@@C#pq>XoA(|vQ| z+2n>c@&nRAbF<_Oy6NIhknvaH7bkDV?x=|9WpWVGUltUtBC13Qlzp%5)2nk;T``P-M#O%@`5@EVV;&f@Bc-`B zp|43Z?<^N;xmo!iRey`Jdk65vuSeqg94=1`R#${BRVqf>N@!9Lr;p&DSS#}}pb&40 z&cB>163~tm?@lXlBS@Y;P;EVI+`1!H#HmG_mst4(Uvg#g>-qCLW3$`0iC` z|79S=_W~hmYhhC*ao$wL#rHU&HxJ)~42-A3%p(l8E)=V9{DN?y=Lj3uX}g*_UXs_Y zGHl;x-eA;#UAWJ@SM{!1KdaC0cWu)2FY zo&M);Hr)mDtS|n#r5)malRY>kxA%6U9hmaFMD9HiUCMY~*4@^4i69^H>&Rp=#^N>o z&n(8GDnDIT-i;BEs>PM1sstJT-Tp{^iGX?+-N{qD1!Sx8j%!rss$ek$%u296kV_xj zddS`ZEob>H{{>m#;cN0zF2x6!92Z?Kbek%PzP61!CzisX=@qw#l+NSj{g$E25i4RB z2(j~p=2O`71O8!M;27F;thg+i{o*&_p_NVd{fB4vD?PiUrG7gsdJPy?J*ICBKkAFQ zJ@lt49;~#g)2>5AmmDg`yBqB$f){?l2A|HN>Os8z1O`+Sb?{oEgxLGTU#jdBf}n8U z8no&y16!uuU{40OekJcP?E*kC5D8Fz2{ofP6VknX+h?TLaLKx@X{@dj+`&`Ucvadq zR`TXD7``^sjWRicEYDhb?5?=VfvjZg2K#kmD%aRae>Jc?)i~AkO*_G=b^VW?pI3YN z-;o*yVoHx7!V7%&xH+rH7K#;s^tvCMM``j!9_l`&f)h2N6h#}ChTc>SxVsWBpUEV8 z+Z4>kZcl8d?vK|x0s6vsWTT!Q?U~)a>3_hZrA3oxxq3z;m5g3SP0{9kT^0{*oa0aB zoJMyyLzR#z4H34L>fQ7{{LS5EB5{<7tTYqub%yo=Ei6Yk$P4t&gW3T-h#jeJ)1&<9ciEdQ(W@|+_ zQggG0cnQUpTD`t(N){d+Bq)#i+Q0V-I8X}v z>X!w`^G@5(`k7qY1=@|R4Trtt{TU@}fEXE$r8_|X7}3cO0IA}tA7f2C2w0Qqa;hbf1nzrL+PJD@C8D_85=jrQ>XNo;p3?xX5a!TR*tgaO$5 zkEOF}QLIkpPa+W!RD6$%)W2GU)1K-KJ^BvKhbW{e_7+j}sF!c|y?lvJ#{LWu6{^U6 zNv)LFcG0D@&ObWv@WD;#`01vrdO@!nM+T1%u1uLwS&Z}RuD^|m{j6^9_6YhdNvj=% z6JL3}mL)ZFFm6UDE>hrX?_@X;(K+VjurEe>&I00@x#suU;oDU0Mf#v zeJ$uwo>T>$+V${#)}F#exc6mGRkbaia_WxiARD&=d9kmTs9u(KJr(UMWPfBN(QJ&z z^4GToXDYe7B46hOyVq~GFY+6HA%xugdJ1xFFQ)S-Qc?+y-mgJxPqhSxN+WbO2kaQ7 zM+b^pbvxo%*`TSIF8PcZ?kha7XW28?#>op7WA{f@JJRN{j+_lo@9@b24Aj& z#}M?IJj_oaw2gIO@}j+80(w&b=>{fXhX?NGfCKTB- zL?qZHrg6kJ14{Yv-7j=P)2)@n-vk|nTiAcY&1vMypz9Bf;2%1|8H0ane$yDYj*j$` zWH!-!movgv?efh#Lv+h;tW69h$DX-(mi2KH&L|v3t)8$rJeN*^C})t^eEzuOkRyW| zOs7;Y#fC1~HNbJE0jJL=CzD~%amE{{vC}@=JkUV#)lzZb+xy6&TJ)KE%o#7cd8PEY zT6b`=MxWJd3rpQl2!@O7-f@>IT%&(xI3if-{L!jZ*dQ6;?(ySxP|@md;)}7zm`)9w z8P52=gCa$TEYFA}GwNc2pgKFV>6ao~Tn99)c<>IdJqPU;f}}~SbAur6Ir8=QIHvs} zLw?og85Pfcub+?~J4+7igVPbfE&%9$VO5StH#dlRzAr5CAlG5m$(P!|W)pcoe=$W0 zG|24`Fb-v7zVfmWZd_X_(nNaf!ukFZ-#)ttR)xr4GCwQ4=A8aY$a0a{kf2Q z&su|{F7s$4wK5U5j3EbwdfNP`0A=p=B;Nx)h@(0|VKmIx;kOi~txt*Gu7c5;D;I7# zCSx&M9nH%*O>?=FgK*x*#$7s@GLX*$=kq(D#uEajW|{j{P6juF?S+qJ7l(7z=iYai znW?t}xB&!o?pw^ye5leZLx+X|J8eF6)JuMSPsH{GmQ#iYdi^ju4L&q^*}E#lyf@r- zR|oiVTWU3b2kNwmFGU1%!q;{pITwp%cM3VI)MJC*Z-ODnF#@`kC}}oXJXio{+))E5bxIBx711>i_t${IZMO>v(jVCovxUfFp0f%)2I%} zwBZLLTjJu9_^{wyb3=Y z)Ql~5ZN9O}UO^9#NghZnmNNGv-S#Tg&2Q+|qd1%M>PH{P!%0bOCRX9!DF%G=W??9ud^isS?i#(~*KYoBp%wbW@3?NEzm80>{e(G0p$V?Y^Q zq)U*8*;;$23&sWJP6HPg2)~sTyL5kue2KG>V!c)eMU}NAZqxC#-O0;iPzGDRxEI1r zUBp6J%e=2~OBGLYy_mttjF*B&{4puA_=m{$0Sb+?UbL&>a3CqCto`ZVlukppBpLCJ zeq)vh5V_hY=LxkiLCZ|^K~jrTm1_Wro^Q1TtBwFgz80_7`ADs4ysFr>r}q6Ixk`y? zou^K$apR*@z4eLd^l^yui$spyvs7jZ0v2+ENQ{O9LglQ+hPLOnx$Y8r^YBt9o-7Cj zxjx-?Tem8+qixq&=;J`^?!g_iRLJK6%0GQ%63P0{vWtn-!g_Sn?8I`dX;b=NqQ)wP zfF}-@2l!(BxK9n&)x@M-8p&FIQL-mN^s^s5N(qx&9XJ5aq^HJQnFFWjbS1yI5=CUu z#HJd)rt({nc?tSL4QF|UN{N*H7Rfk;jPK6g)7)?iC97e8i74cY)Q8zE(RVVQ`h`8p zB$QKJ5A{#~n`SVWZu!bqX#R+Q1bkZ7RRGTlCsfZHwryDq3n^yuMlEqyXzD{NpJi8P z7{78|$M>gvhsMAPYNym{VnBzUkB-z^v0s6@r=y*+JI@7v*^@?X3?Uw@qhU|b0a))l z1*W_oQ}uA!AT!wpR03T2^3_)!RT(B|&IwJ!k;SbOjS%N*o|`pQfJ_R~jv@cli16N~ zVeRO;Dy;rLKIAiu+t_~@nA4bV6iErpFju}|-a3L}NSJw4@l@tfa{w)N`Z_OMQK?bI z?N-2Ptl(sW4en+c=K}e=i#pKx=g7UDp^vP7LnU%km#%T~711|M5ZoTOLyO!fAo}w# zj=SCzmD4}=rBxOL=bF<{Pc4o9$1T)hBWwIZu2#|c^fB0|VP|f$#E&jb^|c@{x9ydF zMcrn&(xq1AZ!OU{ysOaXe)0Am#-G%3A@Id>EQ@p%SY<$K+mD0ZV?w#wsDog=!xBj-X!Sx{QzhMt}a zX(nbvr9;K7LT^p>3(4Rx6i6yBM&M&6_ulXg-Wh2x7Xy63Y7et4b@Z|yDY;(y5@$~$ z0$ngWSgbmecC`)A9L=gy30RA?-M>}Peu)arS}Peyk-KVJT^UXx+>~8Xu~#{mVFkWS zw*LAzmcc?Jc+)oxYz2wxe;5|v{pr>b@x>a{((XL;6My^3MkzPQu5aay?ighLU?6>2 zEQ#bn9*)Swn&D`lC+gBw5fh7lRp$GE52uQY+cH2psedL->GJ5a7JfYJi4UAhgih`^ zs?WBUD^IVLTwo7T%8QA4MC|M#7UXQZ9wxa{8YmF)li_dFGHM{z&*M_QA(Az!hB7AH z@+|kVV-Cgxq-21y-)Op}f&OkH9tdnCgLU?7cO6V*BS1e#OxB`E$t*}xz6EXMs@^Mv z)rmbdWr=I|JospAuH^Rwg>tO}+E8qu{g;&K9}UZuU(>3W8Vu$CLve;zHLu->F;N`^ z!fqN99;`PoPz`#Xp?^5dRS z%0lSVit3qS66LLMcf$6T$NyRnlu!R6Hniu-6KYSaKx53r9vbINyNxRKjE(z}*_B)z z0}$2Q6#QvngWWqvA5nMy$-1*MR}Hq+`=`yjNkQG^Tr$h1HrGQXjx5^UY=X6x3^+nP z>auCR>A+G@1&=5F*UV>iCw;`ReRuc9RQy+ULsqO-|mQz->O`&GsY1= ze4R@=A=+w5u2p$C8RaGx_n7XqIcc`@tlUv|K)pD*-0N`?V#Q%jSV0;G;nc^4dm$H74%Bgrqb8o~OmW~BA*uEHj2s1eGZ~9a$#t#lrk&EO z9&+Z{OUUiKFn1zla&GaiFsD`1KW^I5tkqmmpF!~h4qQn0wN^SEne?S>yr?nE%(0u< zH7X#&rTa^*JyxAmXFYX4c#ZZuUFL@vv=!%U+wPQ$6kbM=xIuF{^}`mLvMGJVR}bqd z-*vJVucm!;7fSIYO6c{^7%TSLk&P|4{$Hen=R&~SLpCp_c@oQw%lqSNi$hvr4=hC_ zRtvcz2p=>T&nCHEd_EeI`7gZZ(c`Gw(F(WOFii)aVlOsfD zamkLKcNG}p`$vA9GB5S#g~wW+B8WbZ^AcV40G;hAn2Ed0p_3O}D!UEnq)QcKK+_DK zyZdh~z=m0A_Bb2h*IN@5u4PrhzC6l7{+1$y^cB^-pmRQUPpKsAU8mQiw&D5*52$QjIw08Bf-!3d^4OwM^ zPcri}O4j%TqR7FTUR3=IL_L(naz8(#Z8@MK$*r<%kiU#g=k&P@03qSOAy6Cy*_ z{Df*!8p!nMrG2i}lFkWd|GGwi0q9WQsNEvP`;@7?_8d$(Jw_*C657!wBrlc?^l<%- za9NvplFx&hm?D@rR#aeKA1+K*8Z?BUA1fnxhs)ponkkeG2ZKXm3pkUoT@maO{MR)vuPdh3rYI>)V*t1L@^Ro>#sL>g>@@pvy zhIZ=X&8YbN<1mHA9rCuI7b^pMMTA~{yp=p9EiW;FaV9lPZP9o4OsNC^w`?&XIh zSBEIgDAIY)oicOo$@f4D#w#)xZswgLN%<mno=+c{@*Bzo(4|KD?5h8z2u0T z%~%-DqojW`C(w)#@8I4R@mZZk^Pkt#63ogQ zO<{ykDbgycQ8Sc7#xxLej(6haGN>~6`~1m9m{axNqVpR5d6?1TpX>7AK#!yOALYm; z@!c81K~jIgZ^U#c7@I-hnK-leqzi@V8A|EUdG-FI+RO`*>*UKVZY^@g1gm;iRN=Gi zi_g2Z9Ss7<-|~TdXg%qUwFB>2tb5q+Z>K>#4HRqU#*0d379@*S*9Dl0ceR z42`^a*RuR#WfJwV#e@ro1!sJ@^Bt`Ll$7rpw{N>|=}PXZ%lX)JE!ob~&Yj_P%X&1( z@d2=8wP?kWrSb~t_%{WGUvufNUzb96uc&$aF8G*2keCe>$K%8lj&=H~Sp6(D>hY$= zg(`w8|MgIF>ri0s=%Z0=g^~aaax`wVBuXN(`__*71*D;T>&H~1kbp+_yMgxtb(wbe z7&U*!5Sc?LfRN}iukvDH_h@`lOhYqBD*hWPXDsaVDNCeJ%^D_v2j&ICkfYA1Zqeiz zfzYw8#sNVt6SkSk&}Fhdi!!FH{Q9POlZV5bmgY$Q%C+bn25AbF$T>=*78w4I8l)Bu*_C)~uz&o{ySBkW zLO3%Gsi)6+NEj$o%fvHw((3joL{WDRTC{ zU#m~IyZfU)vcvz{`e^d-R)`I_EjRo!|gt~0*w=GRB7ygEL<*d|>?i}NXr&OD8Hgr@fsq7C#z_`G&*AhM#5u#WUN{#9nN@k`Eyq0EtjCf54DooqDVszE zEEfbZ$i;QAe|k<8b!P8#*ysK1;Di?u`y5HJI(=#2zrbmnj^{J`pzJy9&BoDwIldzh z?E6&@jh)4ri@O@StZos!BW%!x7wuIjMaJ!CClrX>V9mz!nh*fgckM^Br*G1s?2ioi zE?azJuJMTw`Yu$WDUEM|)uEUtqR7_r=s&pF5VR)^(WqrDHA4+Pp(V%^OxJvLqsqTD zkXYm@E3@%SN41fhng5zO11Q8wxVrKxF#5O$@4B-d*%xuqHVBCh5=-BL3)JN}+3?En z{uz_4&l?3B!hi0&Oyqxx7bQWb8_rqwU}5eZm)?6m%eUHnI%PvhJmfQG{V0yG&oyZQ z8L@;{%=tzrOpUEKK59buIqaL4xAd?7l6OeZKCF04qoWFPYOAQcrg)5Iz{#OKJR9?#p(WD06gSjT;k+x} z-&R8%!ot-Wq_7m4wYtTW)&|M;#(cslu{={x@`il0+OI&^qhqsm@HWp@0JNwi?XE?d zI6FEK)7pq~_|Rv#ON*%lq*??c1@F=8V;4{T-jh`oQWJx8feQ2gkwW00RK*W3IkiRbn9kuV8^2@K#HI3KpDIneZSTM{!eEiEb5BjnJ3^@MzvA_t0KcO#bcHJAii6X4_HkeQE4PH%x{J zf0kfN4V2ZVn)<0zay#6&ji!%A#f^PrhrS;X@jqzjRuityn8)8~{;FJ?%cVyNzItP1 zM1rG=EC z!kt<+P_%^u{*1q5XEx+e$xAPE|M1Boz;Gxxw(?;o^9S8}wt1q&?kutIVk?b*($`$W^lZqyL@ITkp#-Eba4y?TP!&Ly8hK3vuM zA~1)xPmNqk3|$Z@X)YqupVoLnAHC3}8u`R0-gmt#fq;$jzSj67)VXt9p?f1lCtOAP z>~OC7noZYDHDyU~hDUuvOgQN>irnSBwC|IHddAH{S0kt(PY zwcOunc@XQz5VItqpwg2GIL^FzRz6&6VZj`5)x#MA(FR-`;A}$c4gWZrhbpL?O-S3t)`VWgL$q0z^%bCk${-NK2bbGN)^{ zm6%a3;=NhL=xQVqqhE>_QSUB#Z8UuF9TeYoMK8&0&aWC7+1pyjWw|05R5`)n%V(ri z0k9sYN*@QUQ7OG&|0xSI5&N0Yu+&Se)F(glr}NC6yCR3#6IoiGYtWuV1skfzO-!FD zSIEHu-;eok=+|oo=N_8WUr*Hn{CGd=Fq^G}*2j32Qjtr1{jqUrB#@8j{dJ`6tG~ql zZC~r-J+<6@3zxX9^z&>tZivfj3MdAFa7jOxUb_m*(QF<+(0tH#5k>!FsLNb#0r<$r z^FCx|+@I&&)R7JDN*8kY9QGusy2#Rp#%w@K@`&v_0KK4AG)X2m<510BNI09Y&weOnbdOoY(^7Nq0 zrj_Z!Z#?;cC(J5THhSy9-Ohg!=S1DtjvaYfAAaHO3%PopUJ^Du?p7W#2B?`-$);)!1L!Jj})9hG)b z?NRk=Db_n(USJ!DRT?c)Izut)IHeNfL%Rl$4_f=Wyru?x$4aCLYUNHWoS6~Zd=^7R zwe3cJDxrx=YWKmxuplW{F^j^{bh(~Fw$wA@H47mm;NKnP*EYe;C7O?{`f~iIf0CVtx0^dP7#{7wW?M&;tVUwf@e)83V0Eaz zpBGZGEr?;^{Q0Y(APbJ~ud9`LMXQtAM4{0a)WgnzQ~;pHL+Uv&i=|!_7t~q1;%%y zW)6kwwE=P8Pv`7Gn(U8V7~fw|b1WUa!}sx0{s@8@_SX)lNq-T{toW9G%@fNYN<{#c zIiB@#XPCtc3#em*icQm7#Lt73p1+!Ym#s*%6! zm0e8DkgPd81%{Ns93K+1cVl$S?9*EApIJ&X z`Wl#N_aB(>Gt5mX&%e-?7DnycYkWfJ2uDLnH!kDRkjzP*{tPzVliKL`mEwA1(XyHf<^6G3lfwudb6Nhg%y!y46UzUl1 zSOi{MNw5CB{S3-{RY0R%Wzd~tANB1R$o#2@BQfsfqc?a-h1gE+OO7d4;W<+E$cj|f+Dj? z3iTdGB21=}r+%B0n>!ASHg7eS{2ArXH++gzfQ1d!w4K`b$-Wc*SVLa*Y{tKztWak> zL&daiLLjUAfJXTojW*{ZZ{pDMl$@9oNlTuGu@9& zzJOcJn(;!&-BG{usZoxvMlCd;fOR`2tG?6TaU(5hYxqtl{xULHKJE%#@(tdipW2o& z%u?@+HXhA}#>RJI&LzRj^0fL=C~`(n4fjQ@H{+J#(s(d5tBDJ@QRSk%4iv$>{o|FPScJFg5U z#BNfVTb7#}fG03jBJrfJ!m5?niU)M#q^pCh2p*ZjI(PHJ)*ZSlQLJ>wfok;y0;zso zzy6F}pKZ}zjeGCAer2_X;UI&A{P&SK=8!)Z9m&90u3JS*k->bIpLn`LlBGTErm%&S z*viz|ZY;dw9$na0*RJmV zvZms!@igfn5;W}2gsJ}T3#_XZLQj_PmdKs&d}84<_6XtI_@oT^h}?A(UddiujTEFy zY%;R}q>~rxCoM~hPq23*AK0`Ob-|<} zlG%0tvnt-hjKM{`w7CfZr)1aWi1K96y_Pru6tW_Fv)yIPo%IH0WH%DEeB@4No19+$+TzYPMTL544;-S>nPpw4Nv|f0O_4j0krf)IAm!a8e3X5RUbn@J4`iWT zJr~plWcz5h$0-8JY$RkN0P=EFS@#$fBomJcfX=1a)THp3>X^Kziq;@M*LwH9 z!kUqSnL)Ahp*cldkm8Syt^|?OdL9QsfYhs0G=`tkPl`<~60g*2Ci_G*zoqqDLsV3! zVW{F!l%^7WhV!i3RjpNpRmMuncdoY;oa#=2jheDu&nz!2BEsK3_d14w&W^eo;1p|% zc7Kf~J;4+y09c~5cXqj`TTDUyXitCwFf~|0sZSxI(IvQ}-LwiA4pcEmIH~`Z#FplK ziqEuAZ7^%T^7Fd!s=Npv*hDH$+j1#PqtNhIlOyUaGeSljZl@Fhp}R}&Mbgk>G_y~S z)yKHYIh|A0V1FjePb-ZkFofI&8)!bnI$5^z>C@#OFL&zb?gR0@FbCkR%-2COLrW&LeiUU zCnndTtA^Pp`PPrB{?rmL$c$cv4{lO_@qE(PD6yof=P!8s8G2>uZzP6sMRhW+fE9Pz zW75~W)v@Zw`$|2Q=3x8^8N=xaId9h68$M&lnLQQZQ{YqB@VV+X&mU&L;%&2|I%|sR zXKWY0M(o$;Fp=RMs|ZbDc>3`vE4SI882`P?I+Y4J-fUfetemH6v$9)^JLFd6FBukXsapEJWTtI)4Bq8l+fHL%b8)?ibyL)}WtN(2cff(lr%H|hn zTAvksFW=PP;h%_lJlBNrm~08|=lC0WnY<)8G#9g?#)?BO?sF`M-XfQ$Q@FQ%8Mes% zM`Oa<>jM`NlwljuCel0sanXQDwn`hRrXXHjqH3IO7vZP7vz@8L*t*@OsuI+^6aI#z7Xi20XvzjS;>L(c9d-{%`uEh_FZ(RHTl!t!6{n4Wc|_#e$< z%=e&UE&U@4bKyLR6jIiot(rf$Qu7Z6^uN=!fbUk~3b**d=M)Wpz9Prn=D(a3rHwU8 zi-bKyb-R6{s(*hN0)M~fb-r8Qp|`WvO40aN6wcz1cP;q)c@ocL|2pXLjA^r`rJ+BP zxuB;>HySVa6Vj}d0KO!h*V4Z=di`Z;F{v47B#CGIso3g{3xhSJ)zYVp>$Zoa;RCC{h}SF-I1#)5hwml`~qX(CGh^ zG!8E2=vNE1R!21X*5ZFbwxnkP>Y&BK=0oTfkY{ZOGiOq$1#6-@q54p8nM|uHa0KHu z7RJTH?iWmX6?-H1Wzxb;3WH(N9l7q}?NloNeyAZ{E>*>;3pHNp3B% zj{=S(|7mC8Vu2$Dn~Tlwk&#WgK3xNPjvxMBG`(tfmjLV-bq^xjP9 zFiGTAw^IuoLX&7(Qx6Wol$vp)Ot z4f|Jl*)txo?&wuVjVfHgB@+N~x=xD`0)g=HG3hbEyodhwKHtk1`O@})J1iR;y_aEV zV#>T{pFZ(XkeF=TD*}xEIMZltLq*^Y)?2Lk9urW5oy?U(eV!O3mo5|{T|3{O)>Xud z;briYBsgK+SNN7D@_KVGfNrpbd^x_KH_Lf|<6`bG0L#<#wd{$%%**#tvE$CzAxuGg zC{MVN#H8aX49A6|D+AR`~cDcjY9Lm-ooHVkSR?-t;hYW3{l zrogcgI(%#5=*u_&m4mO~m;9jy3l9Q55`~WnKA6@TEJYA(ErACM1>QeS##pLpl!Z1} zbo1q&t3ms6F8S|k8W7VvnQ&+1!~oHgrReO+Kou_mPDk5}!O%_SQo|dW&(hLfn@a4S zPuq4d(i>Bg-yz{mb542w@80CK15u{ytb!sQKJOq!#f8eU|$Z1wS$tfrfhmG;fDWC|3b7(A4ev%JaS4J6$bH|AByQK~UUwy^By3-=4Zl?1hN%z*)yUJbN?V|hi3Q&>! z)F=}ilpeT?jl9si#m=@*IqzO=O81M6rR*_Tg;4STolXBsoxXe8z;|{qj1d->rO# zflbS~c(`a6$tgy;4!zF(RX-R&$|+nR^gpWcT7zY2j<8Uyf)(_E?ZUg3xNT(wWmVzkFPc^R@N zEc_{B5MOSJ;QkMob?yEUax#_`-Px8B>et))lIWVr4#xf8s<+6kE&{`OWO6gm=}WJ^ zyCe06=qZ&^*X=~(GIXK!%61;*i}zGG*&Nzz8V{Cxd3LQt!8qksyFkaj+P&Yf*$!19 z+lLv8bs-Q+mD;XfuX=hmNy|I8xNat%S)w-_W__DUXPnuGT=}Dhujt}zn;loMLpE_n z-Y0T#!~&lC$aLB7E71?CfZkt!Ckv-udYDDidxB`obKaL@?8bd%r{4Qbe!0FHvjNO1 z|77#OIytMLIDjC51_b|CGs(ZSo#$M0#^eOUqX4S>tpOIrO&yHW-I}Mzl4gNI|!(!gWrWID?xEI$< zih-nF-kVpkHHC%{o2}@rZl#c8kdN)0oQU0p1NVmwLD?Tqu2MREr+2vTm>x(}S^JsT+?owJj8`%WOOE ze!RM50Fp1x7)=$DxWDi0r8oE5QL;lb-o2QytFh7ae)eqKXsAfO`DI}hk<$C%2L=|j z;8;`v+WlLiW@%Wfp-KGH^uP4CZ+icFJ|Xd$c$v*HMA1mu6j8O|_NXEHyV@QG{BR?h;#{@$q_fK2Yh#`Rr!F; zsKjRTSpYM`nS>%p#$>IJ@3!3*`h^rMD=_jfF0i>;SCWij^){fdh=c^YrdRburd9=-=SY>LF7tx1`GQn1%^mywv8Gho30O{pa_D&G3xi&PRUyBS2VZJ(G= z9|P!XFRP9}qMT_|U+eWNnoli$T_EIHvvO-7L2)~;FhF^?Lu46$Ezb{x@m2vHibOj> zhyC?fM+s;wfqp^LV6eo-at?E{+R&xaQj5HW&IMCPl-b^`?RXXt9IIrUQ0Xnh!p)kw zGgIPAKe*p!MQ}#4(tFjkD;o<0GnP@>2sN5?r7|JK&+HSh23o_6UBDSt`Jj{gM|A1q zALN|UZZnI~uPsS>AN@^uE%Q0DCx{**DflUk1%M@TwJegcKy_79p{R%mkKo1V{GQ>K z58zls?Ho95fgKu<*+mTP{(6gM5O5z%Jvc!Jjs=!rM8j#n8jl@$L;BwpAB@mP;|)l6 z?~Mjuc-+OM{BS`f@()CkNv~3rkU7mgb=xu1ji5ML&cdVN>W3R-DZTHlL+9%<_D`9F zd(2vYt=ML@v{5{qcz44(aiQ!}4<>d|%zAo_&lq0z3_-OOox1-FhW45XH3DD820-9^ z`ctDnm0`&h6lZTpAv(Ffn!KfrsUt5Z>MWq7yfki`ivejF>xDj=X}|AMP#{y1+Jt1( zYrd10;wRF2ZBMyaAgH-PCNcvx|D{^8m`c174FcD**~*lInxXI%ByN*3&UfP`G6fWwg`N zNM{+T9L>59YBV+M(uy}!L`L~hW<-#6OApj;EM;{o=X;2$`uXM-SD$vKk~3*(aQmIt znQ-bK+ycpyMWrizb1@+oIsD5x$x&={T0yx}(=JZ%&AUmQ<@$8)=@t`amNuxxV!QK+ z_JGSZ@)r>E8+_tM*jCCwchk~d&28!TupFw|U1-P0XxH#6-5=kSS@|8fPLxQmFu_r^ zZh14)8)S3gLqie(+BC%~Us}d``q?zGo%Xpl8k)fMyR&_w8K&L93Ynk^H^KpnUt0sQ zEF>1t+KVV$TF#=ivZ(G;F@tB*88Yw+Pl`YU6rHioX~yt0@7nJiN~$mSCwip~UWX6lY|!pN(-mS^9p?(PRTORNMC2bHQ`w zClEFB4W@=udhaBY9BKNw&Cs@8EGhl2;O&9ROynKXqh8gAg*(2pdF{4Y<<<#aL%we^ z>3XAcqVEHh{Vyjicr(#c`5g8Mf(LA|=Vf$6Y%!@9Xfx1vvFdD3sA0=Nc6yS19#eSv zR?vXNRROv+!!FJyc&vF?HDvOmgG4nB@e^8t^1K>nEoj`!0~Z~d4pP<%dC6F=?S9eQ zP6tA-$4!yEx>E(VCs$>9I|?ad%PBrcEOR9~wW}&V*Q>iBscH2`ZyzSkKGRX zD8r(55|_xEDR#=V89pqON7{Me_7@fJPtxSP6phENa3bYczugAej+ZlP-KKO^)n;?5 zdqUY{Udfrn;Kxh?vysmS;;lQHlrxYSb zpp@yM?%EH(bD0jZet+9X6G?^`nuFTjf}9Qa2?>;%t3|uN!AW8A62oLwNg7-g0q584 z-93=hO~x_Y?jB>fc+3J;V37OE;@ls@b?Jn!Y0h=Zsx~s9+iCRBtkO zb4b3R#DYG?0u$h0^i0{(%vI}WNV&phkzuwr;`movHakJrDwM=^(W%iwrHG$sWZ9j@ z?5_^z6Hsp5)vL?EF2zVp^NUS3ye735IxuNjS`qJ&VMKbu;PN=~$Z;vA`FKqmy92pQ ziY0PQj*t`qzhm{^GoC0Oqa|JLnRoW${syws`qu0QLV^$9RH(hGJac|5&H@2S2!Non zl;ZLh8KZ;z8Vu4K4v$i^38gBL))Ty5iieFC(HF1^2} z%dzqsq?A6L@4h1!PB%CKE%~vGY~4Fb)(^}uJT4jj&JeM92qw#MtG2ak*hn?L?r(OFH*)sC zCMHTC_cnNxqdQzwyTnJ@9P^0`n2yQa(Kfq#3rp(pa^9jX)Ae{JaRQacAXfg$WXjcn zU_b#`V;$r%s$8o&dJnj`{yIC)>i z9P1t&zKJ=J`Bdv-R}CJ(L-^vgCeSs4k~iAAr_@5TF$Y4bQlGM8TKp%@O2YOD6OFD0 z!s(8bU!2znHf-zE49eZ3I$}^7X1)FbbVy)et~|jNE-PD0!fJ-XBd6(x!;G)mChK9s_??14(E%*Vt&41?schTuO4#k+iV`ZdryqC zU5p%MLhSgTqrmmK-$ZJ0g&C>x@+^-JHoQ*1pOmR4q%ZNUZ!KlhZrX#Feu(%bZn%`e z5oj%q(?fry`Ri)*n71!aw*292yT9kcvl=-ed_^c^v0yh<*%&uDsVH=H;sP(JIhuX2 zf^S+~GWhN%_UaC0UYES32buBdQ?v{hT~h8VvH-!Zk`9ga>G7g6S$twXicuJ|O>{xD z|2S&j=R>!5Wue)OHA$Z2N%%j&0TM=NO)C5+TX_p>?(sVvxg_65=L`Q2lYzLnZfJ}} zV$tXi|F!NIfaGwW9CTGY{4Fxy>(Gkg6+nE*MgCz|K8FyJ!$13s2!=xcRgo=9oEU=! z*?BmpI9hTJo$;>3Fx#L%%|F5W(RaEAUO7kSX?*v!DAcY>;Z@(O2dXt33K2&aOm|OZ zHr^ELfRW}$}A)rH)Tlf~# z0Ph2f!S4qPnlV%Z9Zt=hY?StIM)E~EO(^GAL{FWa*Yk>m)FMY2I5bBD{<+ThUvs|p zNLQf{_@R)!gbm>dtFd@}e0VHDWOSa~4x8TW3J>g&k@r{JBDY;h78DGf;CDsWl|{}` z#`&Ou`^hw;$$&wF4{#fP*C~@J?6|Au=FGZbX3o0g>7=eUw%gxk%m)`*eU5^c@KKd0 zq3jw5U1k?epO0my-T{}9Ajg)GUic#vl?*Y*)VD8Knma%YMgPku?U_c!w;zNdr!;Na z7{V3QLbQxgVfgROllG%HN(17&3fivBF>u!l^TUi*G2wAS2UMD%O=$cgM&|=MaX2MX zV%#Ps8~7vuMr1cs%>;m)L+*qBx<432f9bZNxODhqnO{+qO`S3-;svb0k$}>w!F67E z8vu1rU}6#`C@B~FIGE8wJGQyfgVm!PAS92f$!)!1TsAx!G@_01%&`0Hc#hq?xitnA zHd)s#hrwbH&C_s|&#C0aRAH>BOsk z6yDyV`(jCuV`s@KzzbpI5d=u3Ka`i9DbNsDTC!iOS;b5ZFMRrbSBewb(cFRV*`pXBhx~3F5QdXzSW{i`O!fAv)u`=oF2lQ$i14NE8%Y38VmecdC6VxJm~NUm?trFh ze}Fyerq?MK9uzUh{KALF97a5GP0_ze5XP2~!K$&q2;Z-MrRyPuGOfJ&4gF=m&H6&&*U6Z|KD;g;-Xsyd3Tc|FPR+;}}9?qDn3qFuL115mamOUU@r66*Zg zN3oGr4t0e-)zu?^=^(Mq(pi4ueOo$&mMb8`^R!~BO^XATs1%Z>cmSSSC#(D@R$QT) z;EaO{>m$e8ElLw7{BH!W_inS_(%JpC2Y6wtINrYBk`|drlql(r(NyiV_RiL2Nh!4! zY&v};$0Ksfg3w~z!keBN!=fWY6kBg?X5p7w{9NlJur=OPfUp7|6R4A>JO4_SB90L! zPOORqb=3Z%vRUrp)2G9kb(cgFFf-5!iC_by=p3Fe%p~+lPOnXUyaGRqkvEu4j+{u zp8v7IzvPVunsql4BSmx){@;ph1tRyP6^vp^_OP+WYSTG7ub; zocDUa6}Z|coyG+N49=*FKfxs8f%_qs*hGoLJ4?#Uj)A`nuB)AS&UN^E)|Y;zP|ew! zsz{}-nB>+JYP|h?jkau88MCwCqq=4m9)vWuAEGscN<9Jho2!)`G}zi{xJk5_cBWXi z*y6&Ir|~p0@_bKhSfj_W1J7r5q|rY&YCPdD*B%ObM`gZW3`VaC@w4+yd+gYm&dSm^ zQ{AYR<2EhTFpaoWC#D6hfR;qG@Xh>_?UrvC$RY zHgtWZ!JJL6jGZH3X#=*^TDMZ!Y%ojRCL0=}haTIriUtQ`=X2ZVat^3%90h*b=I*9X zV=HX~OTu0&4;*Lo`6Yokj6ZO=0D-ep3#MxC_NUiKC4%(V#b1v$Kt#fm`x(Qo)V&jx zJ)>%O&3+h0IT2_Dyzbw?;= zgWAi~usX*45H6uG4gyTwTS>f)&}b~W+#-2Cj^&vf)%bo;iV<<}&0E}NI|x_l@}f{{ zg0o!0qq@RT+wa8ThOgIzHELtpanfR)@>e9J#7iI{=OXWP!6%-dFHYyFsM_I=las|u zOaeL)UIy@SnGVcI5lS&3hU7AX($Bk#R}@K33%-+YoOe-SdMA@zU&jFZnOc{@Y#%gT z*n-Vfn3lhyVuM~HWyH<7MXA45MrF5>Uj#cmJ=b!@)M+o|%qgJVJm4F6{dgPSy8aYO zl=a)L*lMlI^iX#7`LyOaP2RsaEE>yOTKm0a=tf);AKs2h*uFSg3e-zji)n?3kuhAY zZ>r|Fcr%CQ&j=yMF{p;!h#CV|^od|}7t(@5`8!ymQzo@Pr0eY9uK1Fp2#XTt%%6C^ zqv*(Bozz=D%8-2YRIJtb`55p;%5zaQLC}w=($HXh>5hRoIBZe!Xy4+C$iW1lb_t}t z-LK$ZOBCgMtN8NmXo&&CR14R{o)N5CH|d6mPq`R^^o(8He6rwktLh=d{Y$oOwGm{w zbPF&m!o<`F{8IrNO_F-N7p-!QJCl-fsc`1kaCQ&m7F-wa`Sq>goevPKQ1d}J*sY_6 z@)1-Vp-G}siSXh)8{#9VWehfHzlP*1?AKIvRm@Rm?%;t6)Hzcx;w2EpKuwFfd+U&OoEvcpQo%-R7 z&74FM^N9h&#zX?Y4Jp%u95N`I{#)v+)hP2nhr~!Ihxv+v-|5SkyM#iHp>{kFTw6Ke zO-V-fh*L)c4v2G?zV9V8r8^pf|hbIz@E z&R2E+-uW{v^7uP*(hgj6i_!?%g|N8EFaCcke!6ynFZF74Gv}kGtoL z`P&V~<*ST3+}q^~XBPhUjPEL`?W*Qz;p$=RZ2r#D!O`BF$;H&!+}y#%%F*@WW4G|z zAP#GFZC7z;b7NO)M~5%!*7pBqdiRcpTm284i9DH zJ}gOunBK#^d-vs?jD(oFXV&SahbPt`VbA4-LH9MuSGf2PG+El8JPFLwjzP4NSjz7| zVM(aNd=f*mMlgXDv-`z)Bz^Ivvw7xY;jHSp!}c~QJeoAER7E#bP$>uY+}+Z`q!<=3k=Es*X33G0scRO zuH-*qys|%x4o3UAQ9=|?fF3F@NqWNvS5xB!I=*5;6W1jG;{B3lSXN_m1REBHvF=<1 zN|JX%ObL7K%`TkaX%QxV)M<-}m5Y@e%7A!hPc9eG+1^-g4y0RoNT-P!|lWMEgR_ES~cDe_y`o|!v>S?P6bLF ztKh_($<&WY!d*3(GItI;QmLU%ap;MHBU0<@RkktQHP7tFiDzT2tFA=%CTLFnSQF2pbq-$kzR`)eU0irTZ(|~65_FNI_G|sl|2FIs&#M!C)9JL9 z0Q2TtuJ?2Ys7tau!#si>EhH}UQsvG zaX)2hsP^oans7!?Z&!=%#L6>8>DHx?rhZE$e2-hmUAgWIC$id4To$&7#E!WN?knd1Mn38l9^+T4zP@jAisUSO6D$i%+;oyh6!gAHwA66`j5g`;`tv)uM5%rtK9;ewt#BV)-;u2Ma`pz}bZ} zz8In9I>%E!VFx40c}`9>bc638ovrHv7rc!o@=tztD}uq{WzXCvRogQBcdWJ6Sb-$m z8&BlFw#>;1lj<%OkYcAv`%D)jG4_pzo1L(8JRP}~QQ?f?px5YB_( zI0yU5DM*V@rPc~=%bmlbopdKK zJgU>MNz)FlLG~1>9XT|W^eIm8Ji#lP(3hW$=XvYK$)oi2xeV8>;3J@3`*I9dA=`u7 z+3y1Ey|G`LRn>o?vWW9Fj*15eAM3`VGN75k)Rl#Bd8|%-49)OIGW2;zui!YqoN4qW@s!Bbf$`>5z5nPQx1!5+x?jTAz0 zUfc4++P|&SbDdoX*A93hi}433fGTtu+v3p#CU6c+9E$A{`*jmm#+Wk$Mvw$w=*NN0 zU+{PX)vF-qH7ar~3t0xjAPe;FpjixJVx~b`)FcIzgoc}Hxe7;Nuj_*T-3~ukY9Q65 zoki*2U7k9pRd${GXYC`rJ?aCK>XFdvimO3CW`&RP7<%>9^68!GsZ%fVTUI!9nl2R` zo#S-m*6h_$x!Uv{^idw?iTdsCqd9vre2}(5?DRYJ8tr`kkuXG_u_mT+^Q~(`Ge@a| zW{}n$2(P_8*-GTA#Z#R;&U8ANAu}JfBKj<5(^wWM&e+%uq1obT?HuzMeNK$<;sNAv4B)!4>L#mxzFO6$1RSfrtF%Hfz#qy++~ zSiCElPYyJ?F{)pbyh&~zc8>OK$!7VMG1>9(mHvdgBEhiOHL32LyOh(Unpbkb%c?=W z_OtYQT=Qs^e!JQ7d9d?sM!3I!lc2^5c^7uuXv+oe=$xd;*h00|I3Gy*A*c$&2nDos z;m?4W$^!Dr?fRnOr-1Qr?c16RMNHT)>MZ;v)V%<-4`tl0k+O($U_#dfS_|JawCsBm zs9X)ex|l=Du&>7BY$>MzvRyX1qP~%L2}K|m2mb^9!TqCY-0`s#Iq;)LhHTpG7vU7| zk&w3+xEkazcMA43L9k-kruvgk)vD_kF3yb{jU)Gh!)|kHqSIy;>&w>i1FKe-vTYed zX6{0Rtc}utRidIvlN~a4Go4ijG^46L04k;yS(ewYRgcF-rH&~YZreB@ zsoB{;i6z(7Fw39fHM;Sca_+nAXGf24UT*1E+Ncn2d@`3M`=rVfoUw`AX4x^J6KRzf zd}kPp*qD!nzu; zYyxOmCbVV$bOC4AR+O_Dhh0d=;WNgN^ilJz;v)m@sG$r;rb32Nx9eU3gNuM%UQt6w z>n0hw;woQ5h4$0h$OIzKH0{xNE=c*LGBBj^z%!zKIUU0P+~K=4LfsTLJhrnQRi2x~ zlHnOyc}&aqd&KR`P7i};$GG;hYl>l=zWRq;9ol6j&;xY3s5Vo>2IzU5Lvy>a)O|IN zxocZVZHi)OD4^11b56a)pS15Z<6T2_h3*>gh`E{CCYH!k#gtZ*gME~aYO$!MmP!L?O?s38|#+k z1I|Xkf&cR`9%HmsYn_Kxj}@OY?jkVdP##wy+V}lQW7W5SnYiv^v&_V$oFPeZqulO} zRNAbX1CX6KP52nzI-$IJgeCLZ2ntC@9IKbB+K}fz^Rc!aCz0Oh;z*T_Ln~J&bkWvp zO%*>cCpo7!wHJwKz)E#MOmt2ryW69V19ymfH^X39yA&40>5L(*F=}1p6y!fqfKS(E zI62wZk2!GjUnp3-f?J)i=?{1Ua=t!6)n}&bywr%8 zT`>-Y#L4PIEtut}i?q-H=pK~JmL4#lKQL&Kjlu19i2C*g6Yp3>MHk1rCqUr&kCA%$2g1c9_v@LlN*a-H|;hu6g?}~B=*_8sc(8bknHqR zc8vq??+;22!nd6YixS<#_9P$?oHiLUQp zX>gGCA~M*pP_71PXhT8%3g70`WV%i76bZWRHzJbDP}27Qs5NEy`=K5=^fy|NG&va`N7A+~ zsZst21v2gN%G7~AaPFPDINS~4U_SB6gd@mp>TFH2qm~F&!@V2A|L|!k+9&kEoC59= zLiS~s&VuT=u&8(&dO0Jaje3Bv=?PXb{yvUZCc>A-qLtfGBybRz0`b>AnXxrOo{FiG zl;3pdfK1}-65kmpsJzfQ>oG@vib8W(;*Ix?UF<%mE^uc|ZKsU)J6CR9mdM9p(0u2r z$1GZJRBIKGcjEB?w$-joo%k)a>F`ea(w1!2QPp=9^C3_Z*H&`@BfN`=TZj7xXc zM95_v=A(m#6m!P39F?oH+B%6APvV<{xho z0UstD#ule7yooa7rnFgCVqz!aEYUD-iq@-pA79Qkf=_mI6DQkgWIU-;_NX$Notv*) z9O;u^bZ%_1B%(vyGKM-{%pIWbt(!#qV!YNDvKX})zi4Ii{+PJRU`%VQaNaK!7UjTW zwd(6Ud|G71L$=~|da8>0zT}+<&79a64)Py<3UQflpFK?xTJW(Xsy~+8^|I&cU%TFM z()9NDeu26eT!gpjzajptv3+$p0Jtva2=!?9pR7*G#7wrW@?x?)5a!wK0SvE9X3JJH zf<>bSb&~#82+4nvan@sK?2&4y0!M@<>0h|zjko+bcEZtcbhxgvZX^Ti{h@4jD})_?T|IK_iKhJYG3B@Jz41gv zrgJtg{{-+7KV3cw5f+W51Q17QJA*(wRO}Dw_;~%qr>?tO{y|zz@>%F#!=f z^Z8#0M7jJ4xqD!gVFi+Lc)TYFx>d(S?{mrd9J^(YKpUCR@Ra4_l@@Ko-bZSd&h9%q z+Och>!_@&a*%H77o5wI@La07B-H(v1-tm@8maXNQd+YR>f3nLvGWXU`G`QyIKBFq$ zbM^f#`?YTo)q4WqA1ayH?X5zSzu)c?deRFyStVy`E!CblIZ{ZZw{S?jjlZ~A-kMzQ zlnSbx>gJ$c2gya~)p`6roL959X^#uaU{J13Wifn;@0r`8f+OCM99pFJb-ITAenBjs zGL(zP?#tzp!{iJM97UFj6nQ2%D`_YICNUQxc?ZdoSuj`f$sfl+lGAs=vZl~`#85?A zxoP&#irJ82vBxmDu03q36ef;hr!RRJgF%dXLUkFzAg-qmPcukA8!ong++`yF98AJT zI#y5lkjjuHkC3l2k1-I^mc|dZ@0!|9-R+XXh@;HggSIyvi?K_B^3%A(tSP$l2GqcC zb;W?cPm^d6^AOXbuL8QWyBRu?)BxBkmSef(p%nTljjX`EQ|xgh^uoghW0f6G`2I7PDxC|W?lojB@*qX%TuZcK z!412m+;V5bQcYDb8rhdyh<4sPoda~dbOwhFyHPE{43%|yHNGI_Tx`Kq&$G;zHHc8! z?H8h?xA#b!mF{YbJOr{OmCd(H(K<|ZX0>|7n=)y{Vj%7G^9WOQnDUl>OMQmh6f6ElcA4mj+$^?RaAC!<@!rPN0eYWV3GAV@3K4Q1T_&nbq05FXeCL{=}ol;Erqz^$9qOGF^f_^ z_3Eieow`J}?3(#1LpQ-0 zP#UFB8&YrK8M&EXc(DJn$Buw=!c3ZFba?qubV}hkvMZraIcy|{zC2s2+8<<8MP7hv z4tBSwMY7k?yz|?w^#PBUl*@{-M5WoiU@RIn*tM>U$}G!3&sWD(SC*-zf@L;76coAN#hI@c zo%m4dzt!{fXY^rF)su`CaYl4o&WWdP$B7M>ACFWiRG;jm*fP#`vDKwz1qCIR%%smh zUa&98z0#H^`}&n{_?%iy-4L(C%F)^0idEoW*;cdGrcM%#&^T+jE1l4}MSY6Q9Q{IF zUIG&$DF+sY)aA&|fS>Aq&J{}JttePrA~DfSPmU4&_Hf(gnd{ckq5Ex)oir%-b=)<@ zQL)t-pEiB{OPebnH}F?OH3r#>dwrT+mn!Qm8`Mh4g6WWdWzLOM$$q15iVNBlqfqg7 z$~-Z(znM=es#;`@dyc0jzxx$e(VJ@Vs$Hs8|LcBz!UQ!s)w{EJY)bEHI-6OBkVY1C zyt8Y|6*;?0_Wp3E=vX{;7L*~aXk`h&?3F*(7 za&~FW+A-9%USZO+k#S?0a!DM(F#O^D!$5^X*YL13WU1PgN0}FLa1o?oFFn}x25XhG zDtjQbC2IAQx|eEwv;;Q$t|F{mX8XR1lM$Vf#3C54atlMVD+MVBNPfcG*$+rMbdGG9 zVoKVvAD4U25{0M0eTfj8ywcXWzs?K#BNGK)%#a+|cEAXprS?bH0FT~jj()mX2)$zY z8L`pcd|h4O;_J(l|5zbK-#vcb_>uOZ=OGIl{2GxoSv~Z3=2Wv{6^erW5}m30Onb4+ z*gLXY&v!FQ0n}-Z&8K~3w5dY=UpOdNRd94!A~bYz$r ztmWc@=pH&eT7-GZmzoBp-8{S_r13X3{-n>qv4Acq%3ik<^tXjfwXz2fLuj~Ab z<&lJ*{Q94Otv=x!TpO9cpN>HJhC{vqy!Cn?BW&x}_N-@S1W z+$UU~wxr7K{#)gWB}wkfPZ#cUO8gHkv42-}4V?wo0~imhWRP;*gk7qF)c{!!A_$ao zcR=}*NH?#eLk4wkcTTnL$JDs6hJu-&aYw3^{6dF=+W-Tk(!3S7E^ z&)#%zYrMX1g~4E+%HmDpf)qKK4{8rpk9r@rQ?hwno4K2r88F`zs%5oax&{QR$w^(A z-AF&3Y6=Dwls->LEN!N>&JL~?^;>JTviiFtx?dRejW_KESLncT#6Au5SeVoOw(mba zkds!Y%EMfpKY8`!rfG&4d@3l<0Vk1sOiN1RNOsD3im*KK_+9cOuJhLgIQH7R zOu_JGgE0}QDUg2gSX`V>WT@EFRam(G{6Gm*ov%Eq1tl&e>@)*U96>r9y;o0WOXxQi zx;_SuAdL!+!ptd#dSM#YHFrcPwL#<1sDDYgzj0{8)gsI!Wmf{Y&>3oivAZlP%wG`I z5<7CA;qZpLaj|}E}yX=#(t+?Q>M77$#@bKu5yOvAK|> z<~0KyH}Y)smMU*kVlu-i)n_zQb)Zfz8F_3cdsl2V-ps(hzH%fsJWhM4Rk71iEvt?z zU~CKEMmf@*h_s#o`7srH<|u2O^j2&;ebwXZ!j{p6=7(f%6df%f<{JVfn=6atH!mAq z>5r+Qq{J-i)%$h%|9tx?3XDW~U4NzGSN@i1P`nM>LI@=4larb~^ivo8qQX_`|jH2WHZP_KVV9nIAqpULY%VIW|tjY6pUp3cY31QUW@f!xort}?UD)?M-Vtxu# znIC{%&8EZ>YQK8paw253bEdiKu}es}hVeRduy4~TmN4UkrpHH3znML+FAkKEr4pEe zf5{EF*+g81D@$bruk}k6&RW+Ef+MRU{ zrQF)ZX5Fb=UY<( z)!T|Ik&~&wBHiQI$X!%XvGKXHnp+u4DGEfwH2nU-Y<_viZN{8gA%4uwed_cjajY$n zZG{tATv?ziV!0Q4c$OD;=$8~{6hPd?&O&mfSq`4>p&SL7^y> z7H0v2%-W>n3ViSCvmDtw8|dXV0y(2#VwqzFg}!K&-a%P_%QQ|?34BH+_1QYkgt@F5 z4J?lXwF>O=XlVl+XP&kD7|LqoN3!R8m2-AA5AL-|y0VKfvSMzOalb8kh%nxi2xw9ZsrtI&#&gi$m z%xuukpMT1bu<&urxA>{fMxo8X>bXjgKNNcqJPowi%c>Q;8^5c_Y5h^X2BQXiBG61G z?)OP5W&=VzI_9mp>zkhX4%m!+HwtJB?VQopoY1O07=O6Ud*)=;yvI%CYf)LQ|IBA& z<T7r~`g|dHB{-R5Eq>;bTlY7LhVJUZ&p7X&=Wft{Bb0pj;Kkqb1@8%53OyoE zB!}dTv3y3GG*BBN21M}QjgQD$ypLMQ@cgPbmCfEzq0>W4HYpr`HmXwq$BqHE(pyU2 zjD_LzJO6&rJ-@e~RGhwtEtq?+Ge@a0mD`oZ<#(;IDo_`y%{73x^-a@Ihg|3@QqTcY z-1Ha`N5ZWd?BxQQ%aZF{)gI=)v986kQ~_X}ijGUiJ!T?H>dAXq>gw)nKues{r{Wq4 zE-Z`)4`Th~% z4azdSN=$~-NP7-n?C*D4@@c-Mp=98XtiXZBi^9q`MDQ!P)jS>KK3p|ASE?dz{qoQ^ zQ43SWoBp>(vWF48wZ)_e7)`(6mrj$xoRO&alu@q9ZOP=S6?$mZn~@~a{VW5B(*J;f zn>1%$K($f@pP?g*{Gvc)9aX3+T<;0;gmn;F_J!@0cv1wcK0`8I3PgUb&m2&Wg@N?;hYX1{!Fx5m11O-0;bF zlRNj0W#fThJy_ky@WL~wG6^zUl+Y8p7vR)2{drsvx-;Kg=rSnEwpviMK5bd|*<_1E z+RWeGLXn5g0umqTSdk=$+D482&)Xg23&aeo3=SgYMC(nO&6{2`O>)eSSrG4`XW!V{ zVK{j~IAX3KJ(|}{tK+3(ICt7I?o#^exeBqNS#9uz zXFw@N$I=K~Ym~J}p$VW)(!3gf?6hA0ZEUk--jx*mpO{O zM)VD^ZN3y9Np$%zq<*Bx-3Nb)@EDc(57kWkLXqSS4^kwiVEPjDh4453^u~FLHPnk} ziP{j2r-b8uw{3Fazb}UNj^fa097rK!;XXa*s$)jYo6AznaLAjT7KztywcJVfLLdH* z$xap-1e(q<%k*MsrmI3L^`b;1eKTNpQr7<-PrT*ag^N3(y3&91jrl#sx!V70MP7N_ zJ2puFSF`#45C$W$@8_aRI-5BL1of3vf$l*R4tH5`=caetN%X8uByg(Lkmm2$j1H07 zqt@GI;=E>w_SL4MGwJ@_hd5ppAW-_#;990C9(0zT@Roek+Z!nU#JG`@N5VGwgTa_( z+@kv6k6(A4-r@ePO!TWe1H4Tb{aZ*N2eop?Uil+4WLS`QTo4fPbUD?X#o$e3gi;NC z4u6v&{FfHsmdX8@)bNA@M_3_GMZBJCe;)FoW#!rbBLZxTDK{P~-o#4h2Rgk67f4Q^Ynv{;FVEWrKWwb4&aGYYn~VmbkO;A?{;q``NaeD&mFffa_7k}tEmeOczcgR zY+I1HJA8%M1QK~`ZLvk7FU0riu#dP;3fq4DJB7UR0a@dvEjRyuPNpLY2pfzZqzL~N z#?S6O2%XRo0@PS~laiF{hxWZE(Vpb?{W|`)?@8{9j9tbx5-RTHumga?a22HO3-xZV zRon;(tHtM(mxQh9egCH+hf`_;qZ~Vj&}Q6XpNH-SRy$%ReRz3vqHP^#7iZXw|92Jo@UT+j^%-5`(SFI?uOv51tR#`lbIr~Zw?cG%XS}X0v94uThp(8UQFecL{9Mw? zPHyW7Oqt$T;c|8Op0iRf+1DU_*ibu3hDdd`=*=yhfq#FfOHF7^p?NGSb~yprr$`S+ zGLDe!lB5Ftwl6)6_ysH!b{?^na%hvi_<+080Oe$!l!u1iz_BA(Uw)J3 zhE?WOl@5a&Z?;|uMJUGVXz~y2=$+YhDePT8Ig=$#+e)>8GBS19%@M?`KgM(0)iDtd1 z^u}oP&+6IAN}56U=)$W`i?5U4w;|B<32TyY$o>bZYy2^YElKh8%-xaBz)*Uta;}c-MQ&i84vh7xm1KrtH9CT9(c+-?(JDa9qn-7i@7|l=o@B zk0_^nJvH|uKjfgKKjN}&>?lN(eA4MdPbFR@Y`19TlhhP5>39H{y%)C~s)!qc7)5qv zf98x?PDo9nFs27aYlRHuN>~ew;F2wIilau%(`WmrjgrY( zs*{k=XXn+Zn4Wp?^~NZT5`S6Zj(h@z>%FM(-`fO{iMBCI;{xmw#Hi$h4k*qn^-~+b zLR1ss0V)W$24qL0+tRj53alW|jt>Xoo@?7cN-FuGB2iK>;)ApdX8vmC__Z0jj3MP_ z5OUA~L-v8i)bo+F0(KZAAiB&1U7=pCF`=DGLE;*+E&FH`Y(!5M+_az7!{8^T1<(3L zn>0ab*9{#oQXDvI@_`LR%Is4=eV$&cX%NYYfJb#z)R+i}8&#UabxnC^i;VBH;3o85 z=gv7fO*|K5enh^@PnUGOHfUfQMAY6D&TBRt&u+rBqN`~ZE9@>XD(7@)G9wl3+$vixHGjHG)(*rVUZ&B+;zUck1VE7pF)l<>fp+O?TwC4%|{!6ol7 zgDuW>4b%f)rEFZZa77{8K9IN*IR}!ZdE1|$8NFlFtO&I$&6J(Lo^^_LPLHu|s@q#m z$-*Xm@(roCU9Pd*ljYXKmLJTV;T;R7bTs-JRtMwt5MOP?D@hn*8iy&--3PX91r3_j z8_RAEg%YDksOs>re$Fg5hO-&wx#VxzokqYv#%b>*|4kWu2#MKXQ zAr-i7fveVx`GD#i64i*(`FZL0#-Hy43ui+D+jeBaq3%XUtk!ux^t)k(>XVen15uXWj@hjjLTNOw|0;B z=0v?%8#O=Wc-R)ZEC2Oc(wCPb&~sB_mRf<%+PTil4EM9I2b$^Z5)$D|WcW1|67Ul7 zwr7+28fNo{+`Gvb_A`S#8MCG)i^;F0Ccug_KKn-&Mxmn*lQH>J1X zSD;gY<7B=_7+^7Ew}hq-``?jv2YnvW8Z&P1&!*%yrp&kl$5Zer!@p$kOj1|vXNT3_ zEnB7eAzD0#zMVf`d|rBlDiwDVC@7DOB5elc{P^d){5ZxwZG1~~FfUc^3n?}<+uFA# zk{$PBlLIetvX~9DLKuqeXX(_t@%42V`nPLyO6Tu(I3?%H6!7KEoKBUAn2|y_PZeHE zNK5=OZLnH$@p?Kr!I9~rb9}(cclM9ngEhwec((^~f}52*aVaC~tQay%Mi+gvf|vJ? zr+^?bLxvn{ocrO!XI4<5uQlRuD)Vl@o+9EZpuWGTFnQaH#_s>%s1yd(3z3R8lC^uw4P^I)WS@6EafPzDI5-Dkt8Ge2m6xX>q#f; zI>IugSgo^XMVO-OapL5wBst$F+xAlU8?rs;8`00FHWeuZNXh@eV-&F`J1^iKaA1&2 zJL1$Oa+=l^GnHvWwiz!Wws3YLC~4yrtG{i{O0dC{BAJgk)($ zfFcA5GW%OPFh0Lk@}pboK#ed?`Q(hDqs9}tI^{82Bk#wIgAwWw7lC5ba2C?}E$ffd z<&`d)Ba0a$gc3b`me5z$AP<`(!BhVnUQ=v-?w0WYxn*JhCnt*36}+#T?7WS>xbXLA zzb!vh4_%*Oi=U~SS(_5b$MK`Llw^ambdlGj{!b#zulwjo$%wK}9Z*5~+><7=c%)B( z#dBydRk($OQc*Of5=7>EKU5Opfkbm-#cpiBu3UBUE<@>DV!L=#hF~VNF7R_=tRY36 z{+^HJ$zod9^suszE6w-S?cc2rDxLz&PJe5DtW9%K$Rd}izhN}Ts5f=G<)}N4qe8#b zCZgngwCY_~ai(MD`{UsbX|WLz>sQ@TTYc2BgaxUX_}U8{CR3t zZk3n%#erT4#0!pacTS7RnXT zo7*pf;+qU>Y^GTGm!ipM5~aTOaZU76{USJ$IriJkvS~St$}M?u?TTGl!RAF#^>`vls*(yEbT+2%C=jblYy^I|u= ziL$sDxm_sJ4jglPfRreP?Ec1;U5-WOLbvt~YFIA)*W6CkN!sFnP#h=TLTm*ut%L}gF8T+&d}Ng4Jn18^NQ*6A z)!(8K7S;4ZCeuI2L2{G>Tly(Cet^Z=ZrnG?bV`KbErmk~NmN{Gx`0^4dgF!0NPosy z@PS@G|CQ0(Vs7?N-A+^hJ0&8zRw+b+^Phte2p!9|)TAA@mbZXEzULPnGx9GI$w>W> z3m+JXwBk))X@EhO1osxv&dfxAZIYNQ4q92R~Be8*!I{(!VYONOi@OzSH`)MAr;LT7^ zT$)vSqmkGQ3$6O2^(VtKXA5}$OO*e=nWSDIHsKyfGuobh_e|bI;$G1E`|#HRN@-Z? z-^nLrqB#bL$@XU$TYh*Sts3v~_spT(KW#T_U`f-DEVXZ-oH*yaGQG@uUQHck?EjF0 z+`XgNyC-HYA-rkK0g6v7 zju5-;-j2IXcU9K_TSo6nHYS0)gUuf$PS5zC0OuADC)I4b{pl4VnZrbS%Pmf3u_ndS4{(T6@zCX+- zYxNB>@tGC8rJ-_h+WP9w`_l219vI-Ch?&6isW!F1PfTU%$#k1?uF3Zh zlV6?hezA0%y2c7XQe-CXpLdHy-!~pS*9}Lggync0xUpS(E=sfh>?_YH{a^JI+4g|FIE4Krp@y>;+`T8S+ zjo8+KFHO8I`jlahRx}NS#X%&W0_+&@n>=r&d?zaxw9p5Pf(e&57o?HIbD-iVnDAjOkyvES!S=TBRct%lb;)Q0-yUNvu%_LO} z*$-*;Rb3lg8udGx@8AkWF2_@zlYqWJR#y1-4!ouS0ZMJc{c%4CRaQT?GzHfB(YWL* zvJBlZMBWU17(((7yH)yBZ!4pOKzL3OV^`&XFBWw>&u6)O-sHh|dzr-PcZSv&>N~W~ zHag+w^Nu)E?C-&y=Lm62T~MHc0LNstKtY#%^zxKU2YU^Ec4rg&;n7zekB6hvH+|70 ztX+Y0n8UU2D^(;8t$YL2TNpn}pC_A5eEXmPT+(7;=cLQFd;c^#bS<(FFuSdg7yA5V z9`<&(mimZsT`=R=VYN&Efd5SBVY#EhgVbyf(I2(ftk5PC4@GK)_NJuIjfM71ikS9p z)sgp84G#%X;-I;JJ-`8K1K4-L*YMxb4EW8s!mw}Xy?~1M0t+2fkkO?O60b}6iGZZQ8^kf1BM2v z8H0%7)tijeQ6>8f23l=OTZ}RflZh5t+LRRhi^=(c4kp~~GDfb%Ubc%|3D=TyOe(79#o*6B*RSHBDEGY{NqCVp-AE)~!V^tixmL?OA;Dshq2S{dG(AnPtCr zoSAUz47M9lS>Fxe;jbN$(d}AdM(GAfEc$B-Zv&`wsqvkiFX6oMzlYqfG47J6tJ??( zi7gp8ZPtfMNbHX>r>~WFCBwPn)(R?)Gw4!Id%G(7(d3BL!x(H0M%TCsNyn zErRBLJPmHzVbuHNVU=DMMn7;Fu)9o-Hx-VCvQ-vYq{G4AHbt$PVP1SNFPw!WnQcNJ zH*h4OVPgOXTu@floHoL6Qwo`gFAd9}cG1ZAiGxtJMMZ)?y2G5AjcS!O|6Laab_EpN zT6DxCEcXbegRjv{V*93tN{u}H`K|g-2%2UYZ=(*EK1MjwUm-{LTi$mjb{cuPvyIeJ zc1icXI=JAb5E8$(8@KasOiSBXACI$cO`*Tzl#sY~sV}ls7qh+@UDg0AFAGJ~? z)QWw^;*uLtbD;u1G@TRDrBoQqIX_6wN`mfLGQ-0fBcu79o`cdD>jl7=a+hLtR3{5L zZI@hhn0j(s&u6j@t>J}L$-+gE(%FY1iRPHP;b%i!3`r+5R;4zV3Bz5Tt*_bbTZ!6H z-L6^LObWy3&E5>=J`%eEJkYY`i=lD1{1E1!{q=4*tbQ<|^(+F>uuw5cY(g7| z;}Qt>G#^)YRgY`E;7$&EzG}E@b`pLo2-(57)xV`~vqSpC2tObo^moiX+FFX`Ym@~E zPz5S9%WBf)9NJRue)Z#9{B%}d0@pnLN-@p0LA;xIOwa`6axCytO4?O4`tw_zqHUf<%j< z8F-_S5?++PecAC)R@{VCTyvd0(n8UA^Je~Fk! zt;k=YqfVFur&K)quR3=H6d4x9U$;KudZcY3ro{lx(PpVS^40K z3LV{rxxZIqZQ}a~6r703LDp5++V+n(C%w&+HJXZL?l(_$h#_LqQSq|GFHaf_d9<9x5WHY4?N?h&LoyY$xup5 z0crV^(At{~FN|u++NU4n9xNUH(JY^VBRT3Zc|({h0J1=r!=#oLQ{Kgi07qC0eR)cU zbD^VPZT4k>2QFc*?AH(JQFok*?sQ*v|g_H8UsB zk89MS_WF6}+vik|S7LKcmE)pMr>ot$&+Wkd)?e*Ej6aimPaY1mVosc>;87Sc-{EBL z?eVcS!~Tc~g3Pd|61xSSpyeVzNB5%;E=t)Q4E*#X65$MX?VT2>9jHXNIcHBdU4;NB%la?eoIZk9B8Q{C0?eI8zb3grgD~ z(tZ2+j^#rnk3~;KCNA4#HFklB7r{74fmW@aLP%h-XcR=&@wlnGP$QJbIbrVkE0Pe_ zB6hF+8RQg^#883?AeW54=45wxGu3I@6SIpwG2WHlsKE8+$-pan0I1ugU_N{+d9rpU zd(H`PI-k=4D5D_lR)gJcKjZDe2Bvymz9~Z7A>!g_WMTv|mU}Xw@+<*R5KdO^Z#!I$ z=HI@aGJ=-7ZccXQ(Bp9!ko73y9?)nta=cTUIsiaEPU;6qeN*{*!=RWO^nO7bBl-n|^H-VA= zlrdi%N|?dB+HEVMNJR8_WPXfuJH)}7+=pI!osk<7>jb{SmJsQ0YYYRJkRM+PHy}?7 z{)r~Z*-*`OPS@C;1SgMw{UK(^R_D;8uk;Qz6c@XE$msKRvKez!sO2F2K-xQ@geV#Q zLI=}+6j<`o3PQYKg?Uz(#=T5WVm$y+OuJT6NJ<$KLDDqs0B}Ahd?dpa|Aiw=^`h48 zzlEmh{|Yxz!6HvPPtO;`5-X^#wgD_jzL&qTta1?GDeyGg!&7~5Ibge8sPhiy>sR>B zI~3Kza@Qj1`gcKJxRuds$t7!n^g-m>zk-57wtT*Qfq~;9i;s`*YQOUZ!m!3GyoZwg z_RF=*h2{3JoSH~?KFCTJn7BWoJWQ;PCu&c;Bg_Fqw$8lFpBH81*=53oq!JwwAMVP6 zLHT*zEh($@Jn?y3KRJ`%c>~#_5`Hq^tIr}vjRsjR^uPTE(!Wm{?y;rA=z?tM|A=dz zOC-yH`i-g%U@^=3{l-9cA$dD(tC!`K_q!;8^NyB*KZI7FI;N<%vSJ58yk}O_|GB&Z zlBJ*u=eQVm&UB*O_?^PLQy_(`NRi#+b|{F)>tL`E`C`gHDFfE zyI?Mc2@k0GoopF_kAewyN`fbJCvij@3lIW=41h_+r)<723(6LD^%!%v8bddw(O&D{ z1R<9=r{VoE5re~0ii!^DuKdK##wZl9z5{EVqy)%5aU}$v&iCso9qr`Mj6A){53X%r zPx%Mst>7Io6tgW4VW(M3Z%8{-8RJ5n^?w{!GN2_vZIA{WhEZs#IjBF0IVw;jpkld`IoOb*UX|{=)xQKtmXR zA4~kA#sG@_r6�g!!}AzpQkg~9$>h4PvX4_`?80`uulk5OMCrfQ;^a%WCgH94-TPA!4TY>HcOc+^eu7KwVI1`2e_Ixlp7eDL87G;8Nmy@eUsKr0>!af} z-e}^0Ntz%(Plw<&?f*mBTSmvxY}tagC0i_6%*@QpSmF{hGc%(tW@ct)Sr#)hGh>OF zarE8$y65$*?l&{>D{ECo#EQtu%zgGgXV+5bs&5R+S0(BNZs&#BLTJ`JSb}A(A;`kj z6e#J8&qdfqm~3rrJ5|diR8kd?l58(~foH$^gv48lDGn19oT>L+t8sH7(DOJEqy{ge z$CpE-vj!I|sl_QVB)BI`6TeK?o03~RZg4`R(+;Lt9%g++x??jT_6sQOQ=GxsV0~DF zPibp1!l=TZlB!4|Dj%#QRBUNh6Uw)^MP*C7TFq^`U~y%5Ny$<5ja=Jb)UGrj3wtJy zFo*8f7!PNYBwG*m!V5K~a+A$CZ$VQ@s}EFsiwNgwS2T&g!k@N}u( zYw#dz!+VOL?c|f1lkxYb`@?r9rLm0Fo@KdOembaHdmMo5jHTQg5{ngitjG5^Oqsk2 zZm6_Ew;9e;1nd~%s7otr#F)_KgslqUVL6!74Yo%znJNe|wh_{#O-M?<=a0YZz$AI= zbUkc|jexELf#U=IPS-~H{z`rPQ}2i&73;5M&5j~fMmA}bw}4tS1lAiN@*@$1Y60kbn~;`t9z)v&0eSnq{@`G7yPyiA>CL(dS1y8o&D2l zu#oF3GKMbfhb|W{`!X8V@|GNNs!rGnLI2>D8U0tP>y9c3-8`cGb(ESjQ09S*yKQxt zZeSSrVYkn*REv`DZ`Q>(Nh)%_6Y)|8-*1-fJ!vR4N^U`_o1EHr>N*GOjO0`gZK<{*n#gf>x^c|EwL?PQcF*?* zLr>B;+2K8#D5$+UalU$g65Gu`BC{X)-|PG*Dp3%>a>1f%&hV%qENDkmV+##4@V~Bj z3A)T<1sr#`yx?jqT8W*w_@^K`7FQ5++s|quV<3si9qEkmS^_|up}D-h4Xz`Wufa7p ziy4h>z5_zF%nM645(?HV;z2+YgeV9O5RB^a3pg@ItKc zYN61cvOmi8=*yUTH_y|&mX2=)8R3Ze-%5?{w0!l)9rhj0ob`_r zG++TRp6M~QuE~iK%uwL_F`y+@U5U(sY9J;}q(y6c?lXGmFe9py$KQCnGi-6E-dc-m z^i3N>cJ8&SCwHWiAnZ~GsQ6#KUOy@R32`95oASt0Jtx>e5i1O`F2%kF7JGgN)rh}Z z4;PeViLhXffjWJKCke(QrXJ~Ig)Lsc`gnd&;#t4_Jj-%R%#J^~S;;eQTc3jZ;+?uZ zrp=PIQd~4!tS)20b}?C8YnPU5M15jIxPKI6wtAA%j!ub=)0zZcGpc*(C zD-q6GBJ@)=eNEo(@novo^SdiaC z67S{U0q520>!g{swk=h${rV*6o{@#d)tQP}y$v0^sFGaA<%ToO7W9`s-DwIU_Kq_^ zYrW2HrxX@H-_GDJOl5+PK5sDDeCK$#i16-)F!n0zJLUI=+!wYz%hfA*>*w*E3S!&8 z6UlhG)d%B05Z+nrCKrWeS?K5RCy;^x`mhP^2c~FIC3dzQ%8J6DEnoaxQ&@-zDTLPn zJh&LfnX+$l0(0Ue#hSaXI2Qn#ZU&Ae=){p(~tp;g|Z+|Wf+ zW_SI7&<&hbzo+Py2>)Y~Xs;k+duk$It8Lpkgv!(hQ$W;~KJWQed=0l5Sdr6agRt5? zdAQn)F07N*zwxb#VDVoQH*HeP#K`Tk*E!8{D(p7aIK5$>&xwvV3Qv^ji##UeD2#?$ zb!?+qVM8R*Z`)lPN71PdZ1~!}xJ|qNv#vEziRn{CA*QH2j_++Qtac@w7gm4%&{PoJ zt3;7^YTv2h_AQpy{bsw?uuU&r)EXF>MpXK+XBM@5Iex>_<~(pB#X=4-(cmUMehm6AI}K(`iW zQopsalnk#BE0#3UP+#D2+%<0|4RlyuZ^NQjojhmjq4t1G)|e%-FR9A|wh|*1#Xwoa zrse2ctT#V$S-PB)36^YBKiUJa|4B0GP%l*eG*oqsg%iddv9IwOh5dWmmx>JaD?A`e zMBnOggrxvy8baDcQMkJW!7c%Rgqd*Q7j$Xajs)Lp@`<f zu6Qiclt25TSSnG!c9FJF9AQj8i*GBNh{VT{F3s_hWV#my8)xd$w{wf(SPf`7!*TDV zONud7cU}*T?Hw-MJ=(~jd9RXn3tZg2LRgG<1N2N_JzzC=sXGwW_>Jt5t(bSf6!ctig~*Y^q(7T>1Rz|tpr10ux6 zu$Zp(=J@d-LxLwOas^L3L!UTHeqZaf65rP>R_iGgDRhk#mlT;J3Zf6G)wqm~=%T&C zu&5ECJ*@)ug-h~Gnb@X-7d!dbc7B@*R%NN#}{sdPv-G11`F0N|K9TyD22p|3D!<7vCqeWEOT%rbD167;Jjw;HW zjb4=8m43C7rd)~B{;IYI+R{WeA7Xj=?6ue9&nd&(hsVwtDlo&Nc)jelKD~_Pfj=&6 zKuTk}84;;6(O&}R;B*-+qv7sufnKkp>Zg(f+MUtcLa*QHMEC)Homl8IpEq-p@@<0I zR4SVc_Uxy{kOc&a;YiHQ>uonIol8p3TBFBon~gA6u~-%~)#&O$h;~(MBAj zY_?XILu}^B(d;u~^JH+j=Toq8f#DE}B!8})NVsw7CvW;p*10!XFy|KMQk?;3`djM* zV9UEH+^y+Wa!~$)J7GiD*u>r|9*MUe$^^-&>1(+BXxiy-uYovhG&`DDLjle8fj1^2*Nr!L#liiz^WK31 zAV(8+@@I7*J06D( z@1NYJ+2ee;ic+>z1pf5?nKS+y*-g>0)hq7R;)brunCv2YY^lx0q_{1G%y;~#9A`bA z&M4f`HbuWLB`!)|<)%(>$6CVTum^rN4836lQSlxr-|-Hdt#nmydih%oflD!axQ2_^ zMsME~2Qe9@C&v7(W~u@jkFE0Uq((RDfy!vU?-#Dr!sKu$HVisCg^U^QP>@jpj<#>- zKcwK7UAMqPgMxwv+JF1WRttBBHFVX={G3K!a7B|EP-@qYlc(`XnBl4aygZ0yBScqz zu^Rs5jJ^+0_id|?%*!~MubPO1bjooCh7tKfvnmTZ&vT zPaH;ahoAk41OB?(r5n6Q^E7^K)A8SK97=^EDZs?p(3yme*i615lgk?IVCQ3UxN)pg zV=yR{i7JQt8C7ndOuE{OI_`hI7mzyq;b8LFA^vrEUaHlwU{t# zG-CHfr0@VRZ&5LCXYvCMl_%c0eo^4tegkW>N3a@1A5{KtVu}IE;BzS4T;8mr`f5K~ zZtQfr1U#T?H}EU0{9MJcA5rNmQ_T-JJPWDdtMVaFz5K4WgfLj225kKwi8tZFitC%< zzXb5Lw7p6$$Asvh4*fi@j$l(JIqNRy#}G+_GALNEm~k=!;z)S=NpD5e_nv60lXc-?Mv?|nX937?sfVVwUx!J z-l)gZj-5E5nLJR4!o5)l#$a0V-@#Oiuhc&M<;27gqWW?uW2{-*%}I2sQn(}Wy5swI zgBD16878Y`s1=-Pfxf94EVe3$^npUxGl>5aOs4#`BU_K4TI)3;ppo<-EWru%O8c69 zNyTEb88EYQQp@@YfmGM<4|?4dkE|a3RXzU{Dz8>WXoE!B(dMD%z$n}r-ck;~)62h| zN{cyL_6nb6Z539lB6+GiPV$BPgBYD9J`v+T_^SIq(IK~+d2;3weao!-iXhIp21BF4 zb<)uv*A~am(z}1P*VeV^RsMSV%)P@{VvaRG!_pyCTAqIcw<`gA2skKS)PZvn)6+~T z`TqsAHpDy?OF!?#e{M!=#TAwMU2? zIl|8_G;I7D@$N-D+@ElCe|&@2Ex-E5GzOzJ`K_2K%tz&)z1YQ9EFjDsur)d=ax56I z)jxV>el2I$Fa8h$>gq}=pNtek;BFk+FAk}*MnGmGDOqsFj&pvLQ8Z5SDrGkccl<5Q zI+#`A15c)xnu9yrWe<)D&r&`ZdeRrVSO-h@wZ5; z3kDjY%5n0VQh;?JY~P9QnpuIPFcT_Ae*8_qdVmrQW~*3zJl=Orxu3w`TTigeJ?Nv` z+LxV&ysOc3xhE=-#{DtDryddWJM(7Rb~fLJV?&lKgXbHC@|ir}vadC()&5x6gIk_H z$%d?n7TCzN*OU{Rb{nO!CygRjnjFe^;bD;4$z@Va-jK=cYGofaGGyPIgc?DeVA@)VC-V)FhXGxE4&RkwAZ>L-cN-akNt z^LJdU!pf5q+CMKR#e(7LSNkth>kMtq(07^9ofE5plvla-;(X>s0Uv%CU%5K> zP`BYl`!;2Xob3!i#A$9?mEwWIzXC72Tco9Zj7yRBrALNmjWoQ%|48ob0AWwwv2N&3 zuEI)$lqX?jGsOoF%OL^^jET*rpI{6s&|Zm&?WA}HR&2#C?J7q89wH{RCdC-^a95!C z$mYPncRl@OLp^3J$|R;+5A9Om+tcEZI1R#gYqmto^?j43=jZ0$JR8mdA{aPA7a26j zIfV{N)HLr@*?A+$-=2d5er%UfaC~pIC%$a^iQ?6 z`*uWCyvfyk;kn^L$+tqsx$`uuPCv`LF>QTyNsdss(S5`}<~2if8{-(2rS-VSZs}y) zeUzCD?7C-VLN;4dhTqs~*o~QeVQHl%!c-5r9Dac8h$|#nzgdAevdXsf1N?T8p=Eux z6E4|)6XM|48)C*M@dIvTb$`Z#k-6H^s7BS=97z3HMH-A7pEchnEx?N~IeKny-oL!* zr{(;eU*55|OvfgK;3LERpgCI^G~g|Kub&69?PJ)|M027KrKJ77NM*vII)@OLkeF{i zYt2Urkl86NC2g+rp_+{L4CsD;N!esqC?- z9&Q=Sue@u>8B3;DGBNaoy;QeLKcTHQl0)$QQ{cHdV8^M~FuOc=k?nu&A5K}mg_ILt zzeKIS-&40d={e*#7nu_Ge5)2nu?krtMi+z=l?sy^KSU)KNK8%Dx+lpEkWCqIAI(V~JSfe! z=4g%+X|lpdNtrpWF7$z4O_D06;}vW}JwAeCaW`@t)a-P`gFU#=LnKk*Vaim_6qtZK z*j(brSBKBMU}duUu1I3#kt!L8#q@(J`rY3@7{T$e%PWg=cT3+Bb~EB5$&iz)$77Q4 zen*sUzzg`Ghsz1*+^$q-_gI2u-PD^sa_qZE7a zx0;!hptCTborI+F>3GGgON>)h0hC^mPx3wZabQ3*Z)k{>&_^RWQv4HrMk!0sjJX1%i8G&(7*XaOQgiD}Jt}I!sQl730PhV(h5qW0NcE>pBk(evkfX0d5#tb!&YVDqFYQ?w;Js zkjU7E*WmA*Qxs!IINOc<`TDc}e+zrOX{-N_VNcCwn&s8=2wXxcS17PUduX9w(f!~- zSB>8kVzcqDA-aHlkwrA<@Mo$iYH3OdP9enp3QK9;d+$I>hZT+YriP@Sl=HJMhu^~Q zt5+@;nj6{S`Ixye+kd-JY>QeB3ZNw_hb#^3JYWHm0m98{E&=LNLKmAK^dCywmT z>h(h%f%sG=FrVV5Xd;htY<%Rdb8Y0=#T}?WJ35d41p`^vDEzE#k++4Od<#M*oOz(#=s)A&)kZ zFWzEU0b1+tp~w$9i-v*}hICW`xoVr!Ii1Dat4%?{;>BFOevPdS7C{l9+NL@Urs7?Y zgjnsPyyWW9YnMHCZW+yIA!sS98`6zyw%%lGBt!goZGUHNV~I@kUy>ciyhGk?02@C4 zm@00&oRz71n;i@%opK4H@t5HPAu)>e0cpLRzEEi|Ll!Uygij6_41?#=Vg9$rZ+{3R zxv#bAlpfw?y?SzTa?MUVB&B(ADA-bQ&_PVmOddx39`~mraGP!Og#RDZIZeCt1~ZA< zuY}--f)4jJKAIYcK+WOdui~Z`ZKODVe@~QuLlu@zC{>4Z#Z_}1+o^X>#=&6b%m@kX zjf%?o+l$FugU;K^M!;fAPFKPgo*%wrFy2iiAWH*-cHS4}SLkI-boXOqzC5xKzJmMU za=nT=q@d35VDhx~_e3#T1M%Ibi&bfErrUn{d|%&0zAhB+aUm;>mLugyMzv$_sBpAj zX44yl1foELf%Be#eVIginHb6)k*`<`~KB! z$&dp@vFn#D1@KPt$HW;YbgaCH=-V45`njWNZzt9R_~(4N{|H=jLs~1!3&@W zr7J|%7gsDEC3I6!Qv35=k)R}!rDB#|RnE)h!%+r1Eq+N%W!cFiQFDG>uhHB6WJkYR zC0(5}>|ATe*(tkUr8?+b;5fUZ+r&=>@+{@5fcksAnayxaZAf0Rhr+(!4~Hw3-|Ca9 zOwNusQ(u-qEc~m619+jhdm|tiB_xO7m0dlP;90y*^0hdGy^_skt+LT{d zw=p2@vq@GPsm=fsdK2OE3^~LltFQ~SS>oAb#+S^-_D2do27W=$MLQ8Ie)(@@uyBiv zA7v5GNzpItL_M>=!lU_h;0A9-LBMIEk<2;alTe*ze>X*pM6ADsHYxCPN}t9qp-#;` zrJp`rUeh8*`Fw3JCxcEmDqYQ_wjV61cXf4uROuYT&l!< zai7{7iIq*R$h^7eYT8$JDv=9-NC2|=FlNfP@)_eb9<+8HYS%)mstM}O>YdT;vl1jL zBHC@9MkR*EdtY*`|Hqly=~K?yE&6?~K$==~xf z^)T^Cnz$Jhuh9mRzK2fc!bCt7qFzPUkZAd%g&H>1BUM2m<)f-uZ%wsIt(npH2uMsi z(h@`yf}=jc`~HF*l@3y%H&b+@rW($^SfAo1gQXMp$P1=8P@JH59-rK@#Xls_5BLI9 zZ#VnKdlIypktrD^#c}5$qc?pFGzaB>r(t2i*?DKcpGcQ9?Zt0f$)~McaWOvSB0p{@ zkff_im3{8eNecg+LVD8_4XbNN+G@-pjhu4O%X_vbZ?{K zNQqXxM)w%T#R{B$k`FwIB~pYN+W`-qT?6~f08WR#t1Jjb0S895pbdy2)CpYPo>-Q_ zpnz=yv>ngI!hh)7sYmoC|Db>@XhYXH=KG04HLd?8Pqk)WjZ=JuRnO{=@lA=yJy^y0 z)8P#edCu1J3Ba!|c~v_UJ{iKZPu`pU*C>lko0+Fr|85^d-#thcs`%m&hjQPJ6u52!Nk&f)G zv|CfX2P5V@j~S^xOsgdRIC{KA(`fjnjPC!q95IaLiLv#0pFCFm*XF4-(?$oJZJFMl zt%VcPj~m#c#WY8{rU!2!&ILfF&xFT+GY3W2olLn8+IF{@4ja8C5W?cW@G&=P+1WWi zoDuw|)&)4PA1>b9(VHY-bfJF%8ovUKU$O}#DlinWeJAa>yd1VH(rI!cxxDVrb4*C> zueduh%Aa`OBKkaIO=md0vCoRm@$k$@0g0MPc3)3fJu{r|_ zPbRkxW#)Yi4KE(k+=3JGyJ37Ub@7oMRp5wwiop{#WR2=~skzR*=VrZDMuLCMG+?rT zoDiQoA!-NfEQaxr6lH6#AFQ>KgjUQtOfTXhjyk7i7n2p{Tdt3~A$CMhJ~BMp)(g)b z{ZYvko0=}z^P*Rv6WKTGT?27s0YDSIaEe#$aSr#yf(66s`rEn9C(}L}BcY2Rk!KD= zm#ciIUhXhWyhQq0NU-vdc(_v6X2k+$~(`gs$MqazHjLa`w_EAsgn z%bZbs=wzFcOQf<()0>tgz?S8+9!z3_F*#mDN(3Zv=dJ$IcyQrflTupMtLxBBC@zI9Y?e;_`%wBC5# zYIkrWcEd+UMO0W8Fu33Fd!i35^~{0zK}zBJUMyua2a3K7Pj{||Pexx}RAEWAn)~XY z3{%ptFzCHFlaTIvU#}8K*HG4;KUl>O{A@N`5@E*LguVzLw4?!LA{a{jgc(43o zot@!fz|KL0L|*Z=OG;bmV}R=eg-cYmOK$<01U2TY59H`f=5+H0Mc$`3`1u`0_S+TK zUA0Q{1Zx6;HE64nn7!6y91D}*=QUEd2tVc`+md$wEwkV3Ds~1{GOXNB?}%hm7cKU5 zpNT_&oI+>jp^*j=ahQ)ySLawwS!iwCz~MTfYo@`t3xT|kPGy<1Di1@T>78*@ST_TG zzD1YsOhcIHb-mAsAuQgtY0mwW_36xLLRqlRXf)w`rcF#8>gEB(G+&Tr194_6RHE+Q z@6FbIezfkT6;x>0Aa})p-FJ#e#`@w*KX^uD08EISg^&t&@YykPK)MKdo;f+&cUbXo zl;PM38#^~ZoRT_1XOpN>DkFJ&_hX^Nr_zxXV@z2isqvD+ynb?#P^o^WvF;qhS&*ax zZwi^-quC(bFW4?2b&y9Les>H3KfYcFB%jgTnwBY4?#|dKGlGXN{qsrWe!hO!w1iNC!4(^_DS8R@_=9rxJ*F z2TYtfO~!JH55o`n+!75x*%{NsssPX2U`n}+$;&Xw|nA3J^Tq7CKaIi;~~bk>c!aTBa$dZy^#RGQcav8^x4@q zLdmbsPO!X6@M_+5s6F0p>9`pxpl8%t*b50!+n2tDn5mY)ys~EsjR#_y&s>0o@+nq` zc{hB6IcD}<41C(QC6Pykc;f}Yd+`gku$B{%dTV`N=x~4?DrU!CU4hk;bk@;~I8}gK zSo}1BtPW|xJ2o~cKx8g~_j-NEMS*fkRN4dqs{AUXjf-B4DO}T3^iQi0Gm08W7O7TsLy`QYfT`KeZ@*8hwM0l9mkFR45@NP39SZcAj4vQ$NShX@>m07^D9z1D z6r({ShS8}ccQRQsZ^e5jz}0(T%rP1MQ9Xr>h?2x(m48#($uI<<>gcMD<`|oz=(>6Y zzC0vE=AX$XeYA>Lm_nQ9(H;1zuPbV=tw9Ww>~6m+GUSA5_H|>=7Fz?TLN|G6CX96x zXd99$vjC+>Lg{rel_f^jYA?ViQknYff9W&Q0^jtmfK9D=m_}iuoF-nVNkh4`m;&_^Y+86`r#XMoZb1B(@ zb&t_96a4r}$oxNXi_Uq6>rhd!J<9TS&@Q{OG*0t<>lGmz1NyCq?7F^Q73iVs9Kr1D z)dq`;nre?m94!V%s?m&RIQB=f;7QknpdJYW_Sdda?RvCXk9uX?>x|%ICR3D z$}ErJ3y`7Y+Z?IF;vsZ` zNZvKBIEC4*$@TBJ1{T@kJs8poPaX_dId;!L;hGNL0IJ@@_1abec&}+L=lx1${~I%_ zju`iUq9m1-EU79c1sr09jO$%Dl3(k{VEVTrl9OSUC6+m!xMKep!*9~8{ZeM!+1U+b zBu3PFn_hi4cqSfq_n9|#!qZQHA0@MS__lFY8!RQ|a^sHOn0Ipe49)D@N{vH!H)WAz z&6Se=x0623DJ&C)zu@DTwy#=qIEAXn;Ba2eY?DqT^l5+GRo~A3RwLu8<}!^T?b?I? zGv^*Cs9FZQ{d|IO`G72B;q?u(2y!HWreqVc)N=6pQHfkf^Mx#OveT|tcYbcPU`s?9 zA9S*LG`f&ec7l3;#vR(Oi0NXxB<8ZGry-^_+UrkNd7P8o8afVAwg@_E7PMOZzC-V) zTQAO2z39p2Nq)DT7(n>SR}7X!X}eBRENLJ_v_qoBi8`5BBd~TJM|}9ZfFisXk6k-W z9YqkGV%>*>R0VNZi(823Hqed4VPWVJ$wSaSb|E`+tiepVT+Nz@2wsK5y=M8;U{W&n zQIUM_5TCd(@2h+U*C;}==yf&DnS+lB`qd0!m?Qerc3nu?qd(71E@W6b3r?p5-Lj}i z-QGx|mHg-b!$7c$GAPANV=IV?kQnbXP*wt*e)}7{$J%@uESIlc?JLqCefzW-bN6cW zn%R(Y!YFv9UhSt!WvUJir#K|ZS)7b(m8%J#PqUQQy%DFt^ER@NeFEiT;DvgXXJpJW zRr>}U3f>lq4Yiya9IJ{brOPO37LjCz$0I}dCUod~2!hD{lZ-*?=9q;Op27PUcY0A) zc#2}ThkdQRi%6!Zh$j+Hw}hWAe(@|>E<)GU={5x%#^RdS1>lE2`7tA)E7q(k()K$c%oGf*eTcicgs*DN5;m{Ys z7KoGY{X~()xb$^VFel9LFP41KBJV!ACZ>`}yuQt%<8fnFv41w7!#m-pgYV)4L(4*p zMzXG0`$LGTqQ{a7cIMQ7pH)%dxLwdyB~2@j=j9-04}zp5Yi~8&HtCj#V|6#YCefs- zMWch=Da}~jKb>ll`Do?oVwnybVc^@17LYfk9vDyBojAoP*ufSz%}b*8E$BT**J)1sAd!3!;1tQ=JGjMXVg`cE<6b%B`}Ol!%1i z`sPbQCMZRY?=#8L>Ci^`AF~T{*p!S|hVB=2;P)ZJ3K6wi1N6VZqA>^c(AWq&bGbkc zigWqGM-qJ|#0^Yr03;D%h@0C2qdir7H^<|z~4M)HE({ho0R|zKk`sq}80S_Cz^-T_q%AcL2zv@M!q-Fmjg+lXJv+ zaZjsIlcTi>jM^cry$V4_mrT?Y4wpchtIqr!o4c6F5@?TMXe39Bl{x&l7cyYF(6D>6 zjmUMvT8MY}QIoyi9mQ;Mbz44w{H9_$;@-N0tQDt#>dAca2bUz1Ihr@C(3GLgcLQR!Q;vZjvb{xQ{&A;Zv2bI4%^>> zmFfSEWdC^Gi}Z-9)C3v`1D6M%XU6~#vinC5BE%7p=Bw*h*h)B~KEkIqz{l|G^pA2sWvCtPE=6k|qycj|bfNe@J;P6$k8QzE)Yg zx!$MG@jOB|ywPCDR0Xj6`YR7Z`}}@y?nJcPiyMDP)H1qj3O>3`WTvOjkl2hX_aO{GKNg-;i`*!pjqaaiZFg2NEqxjK7) zrV75bo=n5A*W)rxlFdh|>oc9fM%3mqUnNwSLxV(#J3HR;(z}kY&g&D!b6qs!RX-qf zNT++1*u?H<&aWp)##BbiUrX}JU+1&9IVreq*&BI2kL)o=rp%2Vus5UiLJERLD-pi@ z4<$%DX~JrRB_L_G7Z$ylIr@}0&<~TS)vh*CWVKd(oJ17TM*k2G%lI_eU|D&Ax}g!e zj;{qNw9R*cVQCMhfrsqg%WBUZ4GG}M$G0DL;FVyzPtK=m2bpo@7V?jph3-=NgEkOT z+lrm|!W!TpOf4t3IcmL{=6$Bu%ElAX7Wd+UX0+<+HG$O9_{Y7~Kr3yYL{p!Sz&l5m zOK;WWS9cDp{J?m2DM|~lN`oFNl`n$rEnlncY#$ps%Szy}!`2=zG;2dYpJBgrvQG?> zPHAj%OHsqtvos;S4~2Q=8|mEh>7R4N9*+pJOJk}hpeBPe75S=-IRdmjcZBG@Snba7+Jgf!n zR}N47VRGGqx=|@r(Z8{Vs5&$k;|ur`%*Ex%|5H6to}$vXZ|kwNAaOauz2h&jsWAd! zJ3zUvdHTI?zEL((jhsGhwN`lf7O&PTONOAU-e(ecE3<&XU{(A^&Hugj=x~!b+Tf~K z5@he??E;6G?_=z~Ll6Z13Io&rl0r0SFI=dh)IcG=fYtHtg{~UL8eEb22* zP?TtK*~ck;eOWfdnf%G1QaoAS>y~E~eG28ln*lwm}oW8z8_nm5baSnY|B$vXxd z!GbTHUKAQHg{u8V^zyXYSKLmzS`6Vg&szM%sklwv$MCQZy)5Lp6%hUh{pJa{jy5NT z3;W)pcRWWKipR}((`k4{ipqq*Y?Lo^537cXB!W91IRm%rEGW@v!ky zvb!=Y`ML1dtMzXaYTX{kswP$9V#?A=m727heKGV$LeCL!yk9>pYf)=(*M^c-uUGa* zW0_dXwu*jv93d5n0dH15wW5qiv}!)?m|_UFe6?LS!LxIfHLV4lif?;;b$Z*f6%=YC zs$?^2IPGW~jUTaXt^(ElgpPwEE$~``fs~^u`&}V1qtk7dhcGx6tntQyn229K6PDF| ze)+#V)R|7=-JdS^M%j8G8)XMl(*K&J;JoIt{31)sNF8Eu9SRl zS@7{HV__o1I2kU$NDoOP@r9?QCi|Q%bh%geo0nFf!nx>jT0G74r09OqchQKd4y3JJ zGO|qh<2K&{3`UjmQ}_HZ3{>!b8o{@N(fv`FJt*JIoWs5bBWv^Nmc%(a{ozP!cuiW) zIGXy_rm$gNHA&SnvP3D55FJ6Mjdi1QQe_hFKpsUQ`kau7WuRohbC~H(G)YxS*I%Qd zG!RjL4ndd!V)d5Xl`Ct=j#)H#7>3p>3CqxpMY~$Tish;!FbGAsQ~e}+a-BJsL&9#p zXr{~=jPk4s8HN1l-7+a;iS&NgWG9b+g6s;Gj!-a*bgz`ZzTf4R+59XYSpX$dln3m! ze|DIF>!PEMqkagQUI)_wek7p?FAq!}mTu?lERMQ!LO4y9lY&!qmeSS%Y4ehzRG~5h zoP*NOAYr8X0bA7mSk15j|{+9LXUQF&t&Yq(RmRIR;(b3 z8hbikE#Z72VE*79(R;lO7LQEQFO=C? z-*SJlS(Z%w=*~ydzfbzBtFwOLXdKFeX%+|F3mT1Dci&sVCJu#H&i0KCNNbbi^YLyO zQ*TjNsL&zfm+_W7emd?i-i75<-dlRv-2eL^p3^jY+N(^H%@mWg|0bs}ft+p9McxJ- zxyqjV2drLgrn}k!C2QG~v+jccL=v!~J;(@3Ck#00l6xcdd9{F)k@6Hic1Ln-vtxhf z_k6&`6`lWK_sG6F>q$=%5Hp3`f^tNF8%yLBHlvL46C0X{$S;gwM)0TLPf-zppGRK{ zh}#26V&rC!<6=7YeSE=L^@I+g*FYJ(5OuBf7pG$z?x2NlLOQxVd5CAF2Py)$=i^o@ zsNt7YB5z4>rFw6Zla!n~=^JS+#>n#tXtlSc|x zb}MxoCUu(EEAvh8pQ54bW7DZP8E zAzkraIKlU7rjIJu6L-rzGaC1b@po+4XmG*yJj{|p))T?n^4xEq_plhyS zi&SplSuQ(!C3fIgF&p^&o_e{F&P}6-BuQs?1O(ia+vXZQbP{|v*00fUz@Qw)$ayup zSqoTuJKhp0D{1Zs72wPDCA z--1Au3ru-Z+|Saj0`1YNH)ma4c^W+>-ZB6U6Y2lR1#mgCNpyi9wjqrpk%%K% zuT@BA`)j-TPOuyE`5Etv`d_IBjnYsN5s^MH*w5|~9zTti>DDa^$&l)BWj=?SCVUYW zcRiVOJQS<@?peIda_O~3as^eY4@9AuH zJ>#eFzX77&4QcmU^&}3qq8%Sk-yYPwDsD^Dppm0$?E8gGXx0aL)hp!VNJ=?k`)u)f zft{%UymX1(f|`jwk)Hy^9+ceGu{Sk{e8u)muuAcHP?LPNJX=b?zOY^ zuwEzF@S77oO6)eEF|C#a*S^XFyMv(1kX&nRTzS+(J=Gg;6hh1KB_9Cy-FH@D<0N-W z^j3V-H$D<^=Y>`so-5Fz@-}W}m%g-ldzAB}rQpU@4Y|;VqjSwiG?DN*i(O$nKf?Fk zOgUUKhuA@*j#IhBy(i|e>KUICr?FXKj21cf?p6mnquy>P?+Z!K&{DUW_cmp_6O%JI z_k7wIY5$Ql)E}FSI7JDn_W#=6fUMK)eALO3#I*R%m~F8Ai*2qP=T~w#u1Dopz{iTy ziyp3h|BP;|bAo7fV{uwCt%pDHdqWG8g)z%hKU*StL)`S_+`wk{ukMNTGV9>$@#%`r z^5s6%`$;T;cxXDcqlzn7Pya|&+jgXhxIclD&#pN>A?#5qTuy&&z+F=YB$)Lij2|Kd z|3EqqYS>0f$$@zQmxcnST zqvfV%)HRq~89xQ09iFb)J5P}A&)~n_$|E41BGm3i{+uhCmG*7HthOB&*xv$t@BFp{ z|1s8=1rXQtOj)+Z`I+3Y8(8G67W;)wM=*gniy6CU_QQ^+MR@e+46gR(1F*Wd5KpJ1 z#@%Wd7EabIx90GmFj`niqtO7dQ7ti&1yMCcbktUP&O^OVIZqNuEX(a^X(-^|$i=r6zOnEvGe{NHVWww0T z_3lL*`%Ki(yL2@Rp3oPL)^k!dXfji-D*3UB(|>wyjgh(*3RUk@80E~e8I3mqqkRXC zlP1pl=D)6aw9)z|k9`m>GKfZiVwvXE^n3jU-k$A>D7rG(|-CJXQ%hTAfl?=>vIheSJJF}?dekv8kQoB6sU?=7-N~=nudD!yX+arfr&0| zs0mrxQa@b$J&==Mr^|qApyw!EywMC2uPv%+4_qNWX?FAoo^G?HIK`1KH6g-EA?cxq z(w%d+7>^8~orb?V*;{{xzX(U)%Z zT%Rbb)`m+Lfadpq5%-QkmV{lmV3%#X%eHOXwr#Vk%SM-N+wQV$+qSFb^gG{oXKu{B z5%Xtaew~awnNL3X#K}B+?X~vWzA(kOvP6`ONy7V9d0p-VgpzZ_l@7z_pr=h1P0RSr z@(nB~sK@CpKE-hIOEu#Aa>B0{O>e09E0eRx<=nJoP$U_6kd|xdVyyjT%lSB)*dF=7 z(C*VFb8`A(G+z(ZWJdrOSzm z(y{TLVfO$lsYU0-rUj)#03eJr9vQVK_nin|x!32e}w84a%nzMvO{+VeK;LUO_O^w#ZD|a zXDn6sSm0H)_JYw<#d3ALS(0;1eN5{LwcnIce#l?s|qDXstFZ$0;kOh21U&@PO9Ve}Ht_Hy(9?9}w1+&`2de+on%Q zGs;^7+?q`-D>N8Mj(jiGUyLTwl(i(*O3puHYpaprR$OsA-Yk#F#Zs~WuBjQdFwSy2 z+3=ceKo;bvQiBft1<7ETpPMUvPm}!|f=D(OzEqT!0PReNfM>y>?FN$j*?higw92O) zI~x0E3e0h0?T)-d6~l#UNt=@cV}o1gUvt^4tH~ItgohR6Q}LJm%!r`^zCw8zZh;-; z(a&}&8&ROh!8>;d_rZ_=vd`3+1J5_#*#xU=IrGI8xrYipJo#~_7=0IG6J88W?KjBw z&vENsc(KL1zCq?NDnqyv4om)EAwht{&^0e6&e_bat=K|SaA&`aEkQs-B>5G*+R8hi zhRl#Sx8QarzR^LEL6m;aKaY;X+iS%sLhfP?)#CElv@B=-y$)Ll4xa;tP@}o8tAQ$~zC}?&(_?70 zEQx;1mTXS_Dx>$We%!T=q{&cZM(vJ0qoQ1EmLQ~P=od!`jF739@aXlHhSTGkw7Y&q zO*vj7JMMTy&K)&c)ZxH!5qy5h&YL{BmRTBYhOhu{$7TD{(b7kx34$#^k6dpNHL5gp z2;jboy&^g((1l+52B+ia&gCw?UsF`|$~6iWm(q`1hYSZ$0=*6A>LQic;@2T)4lE@o zIhnCr#9=qZmu1)97{91u8dK||qm?0M%gZs;hG6IF(R2dO5%-k-h?Q>iSuWPY6Y@2u z&LKYC)4rp*x^S%!Z1CtME0hf|c4608+>yo%|PA zpT=y=YbwCZ8FAuZX*zYJgGIDSs`*5O}@LW`S&QtMS7RaaKy8LDf7SM z-eNsItVl$-GPcTpcNqV`Gs|rKu9(JpzSC@>`?x-2tmN=^zc)=sX}*!XCa1VIik7<$ zu%GO$l=xGz^$$>dXAjfIGYr?dULq+m(bpa>f12>nEE_tL%zL@*cA0vIPcrUYnTi`$ zvtCU(dCCK3DA)Un23u()exvPO-P6WIUTZ2OZw1I}*E$i^eto}~SOXvNZ$B%`SE@os zI05QW#lE+t^u{H;9(ep@aniM5bGXs!sG@JacpbbYs{4~yTq{>nqGy(jHhyh(>dQXc zhXPhccq+j)#I=F^rnm5#Gn)|7Lj6M%WtiNxXq+63hy41yYa z3fqO2?C$+nOYMiNaB}}I$!SI(dz7_Bj}JQf*ot~ANXXB@b1aXtCx+NudxZ{<}J)LvD*(A9X9;XUdS$)0(~+GMm55v=jiF4JRC(%HHFi-oVzUV<$&RLf(AHJ@ zeS2yxL-+Mh1*qA_njao(I*kHjwl$ujWLskfH6-C{$0DY~rA}Qfd{01I10XF1`d*KJ zVjlm&yyulth-!P@ck(Gh_vahp)U^K;20a^Lr1ZAKF$dt>f>oFi1wXilg<3(_2L&ip(Gy&rppryE3TR+N z3a{OhD-zfUA^}<-@M;Y8V8lLLVls9{aC`9=}}4vZAQsD|?{>0yleJ+fWDOK#j+ zP_)2)<)i)bRgWZ*o@MLynbV@65V}SuvRa12=)KC$Uyi6?5BWey{!^4+kw~P#(nncZ zT&hm3;=$R1?z~4U6jotmiSheKQ|Zl-ouWnePxPm9Dj^{u5ebPfNEc>EFi(OgWC=-GFXY{Wi~8(u}t-vXx8oq>@?Rd*A(NVZ?^ zT@+e|$9oj8RHC`1!P5=fk>i6s_NaNyPRMrEZhbpj>XqXSVU3UUkp@{r3Y9_L!3w+A zxk%6vwf0=9nT$!Vs?vb>(~I~jT@WI=vm%xm56xChIXxB1w@UJz->*cobzqQ#>0|_U2G8BXnX;WDdvwjFVpft-yFSf7WI6iP zzoxc+mxRmf4gaV?USm}8>wMXCoXX_vKg~+CJhcE96?fPUp19nX-LlWQbsRuL?cu8o zi#c>rq4DM`4IV-rpKCj}>xvED6NojHEF>dwHvAk{S%9p*O7HIzCKH)+8j|OgiD_pd zZq7X3ICai^cZEb#dBx4)&%qm1=U(O;4eBc4bUuP5SA#9~8Ebl`n&M&oP~Q~ZiXN^JF1{ll6M5t-(;CFc)&9W{X>L#pbO`trA5Odoxyx?XFJU< z(0l#91w%fQF|v zL$n1SPrA?SQSxdw;%N>A;RGI>3F7k=V#w{Q8ia9ySNTmD;`^>lak`298%TDG@Cl!l zNCdw_Tx~FyqIARi&Nl&U!Z9VIxob0_eAVvf zd-XXPnmFCqVHET;7`6S#UjWSkUcAuWmwbB1d%i}dOd(#IGi0IcM~+9#rATQ=Wv9vCK{O;(Y5%*$B$?@u>y< znw7=kNrne(rO~c+%i#-6G@n%gL(18``b%OwZdbxBYeG}vgN9}cbI zdoOP-GV58B*~1YmO+-jQuG7bU)ls4h&Kub99at%{CSxr;z#JneL@n=dfWP+ihK=}a zO=!!oxEbN^>L7|c1og$IHskBfrHpw}?;YRa?eksk-CtD_Xt=MgZF2)tR;nDmPHqO! zt`URx)S(xSw%t>!*d}FBFS@8*GdS1?aRf1d@_{;j%DzUme{(U|36Kd|D(q|6_wH0W zCmRiDhX&a`kI5Ml>PugSba(ITp9j;%!Jz8tjA#rsje!FMgfM`I8F#fKS`~&b-+rHq zr)McRZ+j~D*wtM@Easy-wlm;u;XZj0DYoFRqI`;WVz(yt{*XQ@u$<@DlLi_u#|8fzXXq6;VioX&1M5c zAX5=rHZG;Sa){(Y3pw1_qQ6bxm!b3~tLui}m4S@INUq(r7MN0c(8t8Y;hj%ml2gK% zR!mmDp!cEfBpcKC@kvs}gTDf9%00^Lccm(x@~)I+p%Cr{;&Nns(y@kjhIshDFq)^& zl~fAyIOdGT*x2OoL@LVlG_aT@#?>64s)fU(H9t{pJoXBrZBplA$Ts`n2!{rc)j@7(M(TCjm!)J$h=_>r4KM+N&Hes4?slq2%^Dvk{Ey1O z$8&lqacTMD3AG~uupIxU<1%bQMELK*b9jmW_yNF{`$b-6+*wZ{!!9IJ2fTB0F4On9 z?P2tOsPC*3`+u?6s+>-|>a-uKD)N1ZkYofH2nBG^N7xJ#A$I0-}Z-tA+a*DCmKq z&f&I0{bZ$!zB#F}ui&)H=%|M!viS6X z=FR15FxMU3nWd*voqr^?=I(st$;H=@B9U!~m>dhRR_)JYG9&;K5sen^?8@|OGsZ&BlxA_o9{(CVwgR`KP)V2-^ zVcP!%HrWzdtV;`;B$#i|`!S`)Rf)?3341;kwNF;7W1xis$V(P%mBgn4%@Y)q=Bp~e zUcQojY5^+14@UBlT%e!(XLAR4PUJ7Ur8(?@YUAp?!Rec-BT};Pvyxy0qqhufBYs5b ztUW+Yv%>bRO2t-*Lr#Lrn7dommC}}7WHW}L=Ur)>S2;pi30y&#tg0ODU<&%ft~s*2wFw;V<$G!acWuuV zN2k%WyU??uaeAY@nB7!SJqPtu-IJ3FI+W>Wu&lG-xv$T7c=t7CyN|L>Mr+wro@xcn z52cE_`4Rn>RaMF8?9&D!WvTY8s)pB^h-CFL2a?DA{W=1v&$sg>P5CpcTrD1-07!3i zhZAD-r9yI4W^YOUM70Jt2AsFKJNngQn?FT)JW^})#N2BC+TgFjvFu{A@avHUx@ZQY zlhde!7fXd;Kn3kT$|wgLRyW19g_}b1n~0r(xcir=N;#rrFVK~OC$~I!;>8cMcDwBt%EWY6Y*BDX9s2G z2uM;d5<52v)U6pVF5zd3Ai9#!8PTCgGXRQ?#w{`EBUP zVjH5uR$}G7wAuRH=z-Q=e9I>d>QW zQ`PMsDo2<{?)DQq`iXV9gG+;0x<{T)u2-d^(EL3QsPuGgL14TwS5yi4baB4wpTeN0 zI3WO!Ror}NLG$aVT`LxD^e*9!F2~AE<}5Wi=%q2V{Qc;a*FVFo?AiC`%?#Iz<_fAD zgBQtcn6bWMDRKoXDInO|>N?H^;iC-7A1p08Z!s9@PllqvD;{8qF&kBm)4lpM$6e`Mf18;e?T%62Z9cD!09R8cr|_WAO0LlqcmKlQ=WgnXh+ zbz%uG98iIet{9|M|FK0QM!U0+k)t#p&fOh3nc?1W*iSyAJhE!b-Re=p?5Rs#oYf{G zR7x$DhywH@SHb0hpZx2D{{g%mWFwt&X zEIu<;=I$u(PfrFLy)!Dzke{qe9(2#vc$lOtDeIZGmq!H!Pe(v3I>w^gsrK|?Uy^j@ zR!5R-&$WRSH@V7@N3%U|bU3ivME2+}+?i$U!Ri+hktp#9DOwAlxoFI;>Aco+Oj3s9Mg5#Pm zmNZUpx)#8T)owKj1ND2cAuPiyzWEgIvQ(=f%-TvF4wXM_xP9N2=$Ou$D}uQG->_6L zZ2?@Zv{~g^1(*m7&2pSpF8IA0yp%0I;`Th9iM;Ay5qX^SaQ?vNXaV@z+IR<7=EuFj zL1RfVHSmSyRludS%?*NC?qOZx(U9@OSMjQh6wp-9**-ZYK+d?wdlQ(kmxl&1KjtaP z*y{m0d|a)GpKGwm)W@9ugAxz3i3gA~OJ3=AXmA10U4rAZv3i}FQ36-tqOevw(OF&G ze!m2HZollHLBlR84mN5Ca+Xr$YWSqXz$a1=oNkl|<9n{jR)N>JK0UgU)BzQXO@mWE zis!{SRVfr;qfeFw5#VwePi8kJ5vMx&SDYIW^PCDUBjxuiz^eS&-x}RSNTE48j}gHz zIlu2S8X+D2PECde-0gO@UqPdTuBta6C4>{5T@8P|^QvI?Ww}rlI3nr+hQglfyb+xg7b@Br4!sUKGdfUiZuhNZ zBv!)@RBNjTT&d7pqn7E27^^(1RtviJFpI!bmd@cvXF`j>Qp}MyT-0mBvOBZ=dgVCT;(4$8lW09%YLU3u%1HU!(! zht7 zQKW{iHk1rZd8bpcmKCcbz9P}2x(Cq!8IY0hQ;}ty1%+DuO&DwU+(z=PI?kn}PQ*Pw zTYy~*p!mtToN{F!ZT#_a8}+>d_lDpTji1D7QNB>vt_LIyo%Upl#pcGdKOB49-vYs4 zAVF}pVhLG|7SaVB1%bhAExvX+E$z^NDeEYbMK40p%!2ut+`CDQ@IQp0UlZ(0L}*7?jRpsNKs4G zitweSfmxI<6^G=VU{2)thE=%7?S2rORcI~Lw3&eJ2cyxfxqwCH7l?H+ zu%r}lrcevuOx<61jR8Cy$CXuWzN_JsJe8R@a9GLmQ>OP)#z`}ys0jM{cod08Wa<3Q}K0^go~h4MxU(dnP9N z3%2 z746t`GugLWo6fNiy2+_dD}$^BN=xz4iFhhe0eRPd-RZ>)k;2o zn-r)aA1(*_SRxUVUFsYqMDvs*^a|V^F!1Tv`VjA$SIk)=$H%>(37UumkgTZ5cXzKy zDl4(WrVFBp{5;a{5zGw>RD<$1mx%_6f@*b;GD1V3y8?fRTG;9ahel@2 zlr`pGmBjav1R=hL4h%nD1_28xYC>TU=7l*EQjj%7{ZJ6SLJs#1=f+(XlL=Ryz+8)>XG-?u17zw!1(bw`_Kw0fz*YC*MWwgtZ<`027xMh|ygh7;E)fVUF$N>ruF@599${Z)CK-fr3PCX3J zgfiyl;Y)POdIe07;t1}$7DY%@$9zVz*@!|qXwn^+prxY0?Cz0$_3q*c_|V@J>)%Gm z=6q$;F3nv7V;@HTQ!i>ROqe3aq?*e;JkD7s*A+-|k9tTA>bA(*Enj3ueENbGUHa(S z&_RfOM03js=z?6GL`LUabv8#jb*D~g!G#Y5YHOS>>#WE`5F6#edm0XD zBm3mx7<>z-Z0V*j;7AHXOA}(^R4R{u6Hq6^_v=twmvTREf@!?DVd0?Zbj@q6toXAl zcVMw@Ne(R>;VOF*@zN1(6a*ae7Z+?Ra~5)rk~U@!ixTw=q&e-iqs-8@rs<4^r;SfH zOM$1#ZRVIJIn-|ia$xi}G3t#cJ+l3oFxhqaEG^qCc&YA1;_y6y6>u#XO>uBa;PX{g z=_{kK3Qeh7L6->!4z(V`_%hx7H^(-X*AzFk#od&Eu{ieBU!k(C^uXSk-k~-~hJ5Vb zrrxs|rx*If+eW^sGQv1AV!a(~(^;zm6M-X?)yZi6Qs5VP>X^9qud2khA3(Z4TOpc0 zFBCI%Z`&8Ot(tHS$F<{qNinj_;o76V!WWIL3Lt9B`yqO4O`j?*OLvW6x?yz~RJ zXiSXd=cilh4W<0GRGfrIWqvYh|CSbT#cuIWfHswhg#-MQ0;S*6Y_xe}%+J9LbmK(x zWPdz*M;kvjr!_h&{>?*CR`VIUhXbB1!6h@AXNxgkLBU)~Mc>6Q{oy+E({H2uk9+%4 zUZyM%C6pzmtuJKRd;%NmW~3g<2NSis-?aDUIm$^T5%(i>@KU!*jWWD&_5~Q3q-nkV z_%Xk)p!uZN*7+-HRrc9XDW2MbJ-`)Rj%? ze`KQ9+ruCVt!eBz9??yt@XWJ_A9qe_a1}J~M1VX5FVWTM&P!mU#*~M2j#&`YMfksREvv*pjN8~j}giH|-0e_c8ax`PgyhA%(iT|4g zK;2&zUwcr3;=KoX%=G=~i7HEOK3n2U58l;~T2Ms$X#0PuLz&tO%NXs2xBST1?t6RB zC5JAj+B$6iWpw6bdD6p0reb-{&!h}A*v+y#uM>s7kN+p#C$f85vP8l|7&S*v;4jq+ zNI&aoIBDF})`xWnm$Iwisw7%H*7m#IArH-BiDgd~6sU>R$!|Z|fgVw`nUpeTab}+d zn_`4Y3XBmz4p$_(lKJD#k|4WuKEs~qTT@rd;{c`IEkj0T@>!$Z3X0fTYlP2e_W1~?UpUe zKT zrp+gk6~purN8m~_8P;0Z6amLYty<;m9psk1_+}6K-5f4g5)7l#WyvF?t9PiPCH^DK z(II*`{;~aLS?NzzyQ2b&HBI-Sj-3eHkymN43GdQj-XiDurq&&*sT0Bw5W6>&; z2j-?*cLsyn`(ms0JRfHkX@EvVGL{DBcDrYEhT!g$$DOjDYSUvpzQ5R#nPcxAT7S|v zddjw)!DdUn^TIdIa=s%8-tBHlcVPvKsAs>-ZQ#zE0U9SXa)7z+3K4i}v6IFE~)3jB~z z%4}y%Xn3s`@vee3{G15FAk-hJqn)V2Mlk}j?>ooEeNLy`dKPP;Xix_GXd;|@oDGIt zp9sSR+>M!ATd@{{NhG{WDlhOl{cVC&sPjleQC+*1^OkOxlEZD1)K*`sf*T5v$szi%kLPfAer8Wg^Up7Hi<_C(R$>$;-5?)L{xhyM|uCCxGUG01~~b^0i}rF}KeOh!t|lF@I;_*+!a z({wupgDnc{ibLI+bYFiP3FwX0cut>eQAfi^N$l~ZUiU`3PcdOi?1?t>2|aGO_7YGe zWVPgK>Jw6XAep9fh!=s+axpY8>q0+=>Ejx`NmQk+hHEbeDhtdxoR3%_&>#M42jo8$ zk5AZR>5cY%SsH6%(K}f2rzASYiwtEMXu)WU+|f_G-u6{3{{Xyu9TZjmXq}}dN=Ses z&_5etK(k(D+l3u~CYbd8)OCJuNe`h~sIiQNhQY$p4EQzn*jK0gHz9in4JItAOXeIe zq$7(s`|B6L(k3a93^CcJ`Y2gN(=K-pM)>5QSSVGl{#${~qVIHt@CPlY4KA{jKv#B@ zmRHn-cGpre$u+_gF0DxEhQ<5d{EL;~`F1p46`o=^F#I*Ah#*!5h4r>fNvu=3LM|ru zY*i!ywt(?W0VTfsmSl`rn&6?}_|>GNDi9a1*J9OGW}x@|6pNFJVMMxQMu1eK-z!YB zPP^xQl!VS;#rJzuzvt3|k2&XdrviTT{}$SEtkwZ46_ka3d`qxi6(c6&i@K{Y7R{gk zV91D6QW7l@F8P5DgD!*nav-{;=ZEe(XpZ^qrap#Yv$t;u!wL0g?WB4xZ<+GvUn8Vk zj+wLZ?QqD9iQ@+JhO56$WDlB?@(})qe;1BcHfaP7r%^Toiv}t+0mxGO3eo}RoeV%> zHt;9J_w{j~2j{}$_m%T@11v^K^=Y?zk2r}}?)JgWu5^c`zet1e`_(@o>PV&ny+g}B zZVZJl&;(K$Gk{cDd2WG!r+Z_J)2VVSJo~G7A4ny*Fk88I@)!sUDb;C7GLME+Qe5e^ zjt2_1AMs^E2WQ4c^hZJ0l<4hOeRX*>YlHYm<8m4FYFGe+s=Iv+6oWEb0GDcwqK}Z1 zYD!=JO4RUt;Snce6Osp-wf5V!(8REa29ax~swHv06Pb+_NR3LZv{LK|K_5&Qd$adD zNXCMn&uM;|0J*KFV)rjZ6s-Wc`+!G z#MUw(8#WQSmv`OZ6GRhCzuaCkH-7)rvm&4n_m!C2mrza%dCZbnuM6(?S6f8KH5$KG zcPLv9KwJel8XfVGAbXWBRY%A%qOh0X>_%(PHy>l*(wy$mGrfLk(szDzQ7)U2#gl=( z57o@n6oW&%F_b4`&}9p%K>ceP@lJ^f{T7g`l#pQ5*krl70F^XicyFC_OL-hwVNUNi z0ag5cf&sap)!JH#fwrOJ2zS*Vdkbu9K(KYL+#N+yJY5(WcI`GM#Q<1DbD1VV19 z*<%r3R7BI37ZB9t+gLoVA(rc>j^?VHHQ1eNnRT&*t)}#0-Dx>jeqY`cen-8>NtBk| zy&t~KU+Vnrp18JabflIfoaVuIT3$vs( zZT(wn?IU<)`M1YHC_gO~N8w1Be+}5c(E%-5ZhT2nodBWobohx5lsi7yX#j~kbKQ=< zp6~`j+OK85b(>!1{#+i)N%zB^o6b4VP(gP~(qix!lK0uzxQSKQM$YFz^IK&gcM2kT%vxh4Vcq=D?0D4yL`?oU9Vx0&^S zBO#N<|BHl7Kpv(z(Ps3#c3IQj>@60>9*1Bto~Z6a&RJT*8VnJgcHS;geW@Av4-IJQ z0f_=dArX0KV?sju)W)K+dxjTl&lc}^N)sPX>JB^OsYA)>*>?Oz?f8#BoSXdQ4iBnk zy+@v$=qO;XDC0RpfEM4}PyK<40B$>CKI6OcAp9SCk|aq`E#@EP2A~|Js^V9=ecyja z{iguy$A1@KAt50lFu?u`dj;c6J6vj#(j`U+g#f3-!gGEow`==n3$rKq{y&tN|5#kW zu!Y=YDE}qjTp`Yo(72lq=XDHnPIHBt6VfZw%_-^Balc4_IFmE*Acee#Q7_0OU1CGN!DWy&1@;9D za~wSEEW9nlEKlz{5j`taFa#W4wW(h$C(KE_r^|F(#V8YJdXYa7ydSjimgs&hoU?^A zIS%zSx8>SPTd6+uu8M`K*@vnhqCey`rbP~_?NR+NC`PAoYo|2h)H#LFdQN8XandqmhX#POnQ=bTpFMFO~ifXQ3YZ7DdA5=VA__mYFOd$trHs zm?Du1?v;;At)Q&A&q2{T?ah|s!8w?-c|fY;ZAKN#`3;UGO6TgYE_3HDu+M{f_J4b8 z(5Iu;C4B0%y&WGpq_-|)T5EX0e}i=IW_db~I#vTp)II~ww7^8Qf7glE_{P0*?Dx4+ zQ1QZ%4;uj8<*PBhrLDbiV=}CGDmPs!baSQ;(iUkGWp&NJ-U1^vGl4$KubkJR}cq5=cTZIyd@IXXR zw9#>($O$%S_h0b=K)^sEDy=!kn)vnH&d+kIZRS_J%qZlGTG4+V;dSf%JY|e%2OsM^ zAi|zczlY)e1P?ztMY`GeNS0?Hvi#QQ0wJ9lCd+P-PoUw|U+T*IiI1JH2~ud}BMMb( z6=;^o)$f-W*l@%esqT;p+KMAm;Gt_}W)B7Jfbl!T;3ko~TM|WAWS~x)&*qXG9C7l1 z(9iG6XaN!SYwoE)#F2w-Byv#(*sRTRfzL5KjQZ5q(rgygS=iIMMOi1bcx-c5Y?h?} z(C;;=d^a0#n(&A&(_>i0hUt_(g8&h1nAuIjNqcmW;Uoo=#Y?-5d-7JY-`sJD5Yn<> z+Db?9z#v-9bA({?o+-}D7J1<^DhM& zL{*#+W!xnFG7@uG-5sK)Eq(UnsY`eTgZdmieq0wnLNYd)i1Rs>veOuaGBn9;10AxF z0E@FPR@*$Kkv^Tg2oBh!@S1-DjT;iuCL#PWDb3}nK%a(YNM?0hSQxY7maP#QT!F|Y zvo8Fq=mn*6p?Is}jLn?U1c8!XgBKZQ?G_nIgA0X`D%sz;bKxMbr%U2G@yzr()ai^KX1mT=Uq>PZ%^VmOGavhbvY-&-M z13mW`344f0;`KfoOUf*hM6^S=6y|BJoLt>i8iF!)vEvDud&OI)4u87*|70^8S3ktE zMiy(5Jna&YsA7!1p8`R#{TwRozVj`nBLb^8_3&jZ2tUSCK14R+6jiML`x+gf{DrwK zC}hP?UU4rXqW&w$$q@sZgpPl8PVF}t)E4H<=qM-9O6gWBz8?0;aKp%wpwklLQ+7M3 z_bW2CZhSf3aP2%){;}hoie}a+Tlo{7M9NQ)y^YbgNl%0F;ma&zhQ#Tm#4k!X9858Xb!zVIsQ(!%id0aC3(0I?3AqienROf#5etVwx;Y8`mM(sHm|f=%Lj(R zHGKS35U454Jj~$Wh)+bPl%O;w8Mgpwx0!U*4W9YVceIph)#!f#l8j4dPBD@;fPug_ zlJc(e(&Uw)N#IJT;#~jS0*AZY>uQ0#83=2Uj^i3?-}g)5&j*A!o#%#>;-4NNCbPRf zYwuGwD+*cOuhTV(Z&P)apJsJhKOEX3V&BpS14Thx@bJiSw)_H)%`OHt9_hsR+{u$7 z&~Jxw!!JPTI4JCE4VqBhAI{qYj)Xf9{7pSKXFH!qO^$3+doz6f43>soZ7}DtYa&$@ zxbbXHPE6TkoSwdG#Po`s+ulerqi$<)l$1?kK8(niQF+?m4ynfQwuV1SdU5 z-kE-#Qc<3&t}Sz;_gePMFwF2bJxb9h>Ol{vB7NS_#UiF`)%gJqYCgiIE2X^cfBmeWVaCN!)HtyIgDU9>JIbbvB`rUO=le=)ZFRKFMLGMuTY1eFM}sS zyMB5|qeo?IqK$t#kJ+PCF^IX8nR|ZEMI`!~f>eL(-yds9+1d_z?>gGiJ|B~~e!I;R zwb;`ogqOsWrxVy?$X@4cpbt$4E8^x6Xim_LaHwM;~jsZw4{zW)ilO! zu*iwH?GDm++-_)Z&(|2bck{JoUZcNdXO%U}=V<&_kGpwvM% z-OjlsCME?Jy%uzCFd|d;l@*L0ys49jkVaFFvF7eN4|_DTjlKia2=y=3{y0NHz5@~N z9Y_^{kcY^haL4{?R&1r=qR#P5-Q15_jU~p@2rDNP#!926UNsDT`Tb>mXZ3&oTMOWD zK1{;J+Nu2!8;UHW(3p_-*bfO=B@^8)+vdCAb&+ovT_$7VNt@FKWUKvV80Uk|ub34E z9S<7vbky;ofsenG5@D7lJnyAUN)h*Wh0n)bg+cwIU)q;S_ZFH_dXZf77(Hz>ge((O0xo2K5!djVYr<*e7uV1??-p<6q=?Jvh-VtneKfsB+ z`J|Qw;LH_~@N6!42{T6X|Ej1p3?jk)MYkb_lQob2`Wk;X>*=H|lV+{)F?E zVPZP24h%2nUTSCDoP6L4 zV|xnqUPqmx{`ME3=;gEX5N|PlxHi2ciOB!Ji{gt{iH@az^&LVX&<{pLfGe;^Riy^k zyOm6G+JD6Xh9YLoPVXxu%qm4w8Tew2)NJI!f~pZqY@RIL)3Z{Vl+ie}faP3W*(A1H zdB^j6bNg8*7Uu(5juvY_i-g>AeNZYgQ~S$aFXQC1SV)iZD3)4y(x^}_9c3M*q!z;+u9Kr zAFYr960$D^RMFR(S&=DxhaR%&$`*PP0T*$;>6^Ui*fN>3N+W$yz^iwjm9v?8xe4Y{ z_`6q;0Yh@%d&YHQs@@sC@)EPl4mWF~I@e;bM!)1rf>quRU1xD@0K)3&I$gSl(Ft&07zQm35`VNYkf0pypjSC z^w56G{4}(j4r0MTskSg9UJSMC<9nc5h7y1={2M3){sAZYZT;WJvX=L2DFQC?huRHb z_=!fXrZesZ7=vOtfUB8WeH{!W{BS%)zu)RV`vU)KACzl&Tt3Cvqp5+L^zGA{B%THN#T<#3b3$h z#u{C#C(v~CokzHJ?D!#6&QiGDC~VHl#B0AlO(QjRxYC@X(fO>kX|q1MwEK7)8&+`2 z%%7;u<>yFR=W>P4+^#f`kJ{aH_U9i?4ZTA#AS5+LwcT2%{EBZMn~4x z%+>=jyLiwP>5@v;9q(gpAKzSL9A7(g2V-X}U(}zDO^G=btC^ zJe+!pU*``f-l@;08J%2KT4lIhB@w!yy1B>}=X|?{;0HWc%mA z_;#`1?)RfHNPssGTn_v#TJ*Hrph+K<663w6$btr0VXC7B!d_|VoXpx3SDyK#EslvG z@;p<}Yp>vLW~KJ%UTWfo-()zz9Z#W8+3gSgehqOh@p*Odw#39B^t&=+Oy?!7l*90R z>S8~PZ(bx_*(74?!E8JILNJj{*5ipa?(o^*6{G_54j(i@XaB~ubXgw1Q?CD%Nz><< z5kofWADrH#A&V>tQnRK-=<1MwUz@H{T#Z17k5d52f8C(xM~?{0{8P4R11wf{H-TLj zNv8>;A5SN1EfM^azAky8K(NK!Q;0 z0ji#qj1Zf&m{u*Vt$@VY`sOz6L<3%hUf;c(cw||_1Ip23AGBv`PMaI6>_rj0_#{HipJ%;JZEV#Wq>4dh zA#0aE=4MwZ`O+J75qI{^TXniRPA3g=$jaAtSbWYQJi7B*cNwiLZ?`!`{!tkVUWQeu z1kkRM-ydpq?c1dD_j2-waogDyR7x1*-rReW+AK3e!ps2Ux1xc;K^eVR{{7@`b6AWHvp1DS zg&FW5MY7Fu5Gl734#|?Ny{tSEmmvZ&Di&%njS(7%$#6W;#WYeF8X?#+LoG5oxvfp- zdi!>Q4Jy+0KDnOkio@CxO03wj0Om`U1oZ5B_V|lWZhD(O*1=Zkgp`OUHuq56*1^Fz zB2|>x-gxsMj(_jO==052{rdd?4D-08mmYq41$6Wmp{M%P^pFiuw^_cY9&=R;#Z#$a zeMS{(s(dL_{JCRCM0ROu4F7S`Ii3FC#+=v?73hiImAadG5r z0AN4jj!mP&N0uIrU;E%g#=2NDVFC4|;zF3a%SsZyxFPr3WJ6M7=j#D=o|PAos$%hR ztz~f=CL!_YS*=!_*^*o8U1r%9r|>0^lbudmsjCIOJu(H$sa&Z9gNgS#(TaG1d2B(` zo`xHV0M$25ZP!1aGQ-nZO5(6b_51mMPwl}-R=?hwa_t8qv~=ql~XfrLLBMzOqC?yH-(JeQN9Vl{_1UGt*A7iN9$3_e~4 zdcDgUSf2)(F5z`>Uks=8OYOq>PjwPQk@>+<4!B1P7V zV5Uc#bfvKUSl{N;Db95$Sk;KL^52%~21P8Tock+w6>t_YBWR zQ9r2L7a_J5xDaQ$d;&9j!{c399cW9a{(@2>n*iy2Y4#a8xoh6Krd^B5ejr zEf{&P*7AEqVi>4*bV=o9U7+2dGrhT|c#$#iwQR@B8y-`=fsMPnD~tkilwan3P=yka ztI44XIuUBIO9?Z(%=p9Q=&c*E9^GrAio%bQ@0jZ5!78n;nh^r=&y=BJpP0M-wv!Uk)cb-Qgi$$Rj2x?gy!P4&PPZ0e{@%6?mS6 z3$m*vPP1bphetHU=8yeIM)w2b_e+bOD`#eywymq^;%LOAZNWhHjN;Du@@{50y4{E7 zY&t$i8fekjY&2UKXN#n~J5Le>4k$v-!b${*Y3hfPIGmXXng%Jf-1BO?TiFe!C>Q-X znM|%c?`L~~D-juke(QSx3RT(e;=aM9BYu=JyR*v~fQIq&kavaohZO9M9RDhw2N{N! z{%CnuN%CYDy4p`Gb0*CY+b-CoGn~<|(QwCndiSR~Xh+;)naF(9XX2pT?+c!=uim6?HwqA#Eurt{piAbx_5gS{7+vVeukdU7l z8Rimy#PJ`D{!8#!wYP8qE)Qa+k`knvHoVzsAPIBN#oAy@|I%$-ne zQZMaT)oJ>~#g}AlYVgM*0LXZ;g9kX+IQm96)>hPKS9011NlhTbDVim~;;x^ZUi$X{ zs{oB}T}9KD4Jut(x4U z(7+KC#Xsl$+@@0_mU9V7BD(-Slupe0gl-$0Xcc{(HG^v{chG<`JA7L&dcq|Px5noW2(I=yE z-VFB>`331*K#{b=wfwG&)_<=0haoCpeU@9MMVGQHa!_b#;#a8#vLB6Q(ecYE+Fw?N zzwMbqNOQrfkkfSJEI39KIBY1z^pa3;tCnkQr5|IT#Yv&#!?QU@M*^l&6!HcrLD@s( zssj3*I@%nT)XWcl!P%Oz1^%%xHoBZ?SmsG*8;PRKT$Cd)wV0zs^idQ;<3I=SOlj-R z(G{N1tE%6oX3-EaD!@wwWKzzU&;CN)$(=T=0*k+B`-> zhi6O+!#h@6FYR zb&Br%7%txL%Zbs#?A!@9g+SqsuTQl@r!!kn-W9t>P$L65H1U>c#f(D~@eAOKEI+n$cDrHw2_N2jacJCs`4+LUE z*VK0Nr)*t`@EMi!)sdvdnoK(nMIIb2P?Fi&*S1`cli3*Mwd!5ZWAbG@$#^HUe*W}W zi4@wmRvCCR11~+KB}!BBzHVc2+=LP8;vBLGYL1%<4))smP)HvZxvo#p-=^6_IhxW# zq(Y<8D|mLMIv2E7d=O+Jc9-evXtkn~w*f*J1o-qqI5iVgd>p}TPtw4U0Oz7_7L`=- zj1%bk5;-rz$#H?y?hVhMmor^HCo$@Wn~A|Q&&~|&6Ebi&x2vx%B48JTA$t$aS`I~0 zFOVdf3x^iI1760>tl+WbSxH5YiI;DWB$8g6YjT&dkNkbtcyYjEO*6?GL8f%7J0JM+ zHR&1OZkG@P(BnYE`uLDY`cYyamBP>+1ufVj%|@{$`%&$x7qn zs8@r{;ApVLv9G|fPi9OKwLwE+G|w(!`+4&3Qs z#j2Bj_yLUk;KZx|6igO5Nh)bz926Iy0qhczFdFyFUXT1NVoPR>pS)mBozRhKyvQF- zJN*1+zS%H0nl{8fYFH~QlyHaxaDzYGsZ2yiCi}FH*aYame%}BjjID=H&pu@=~BWKnn>#sh9n~xqG z51imId+Oxu9szkCoI*rkeJ5?>^>E^PfGa>WO{}p|!5F1tNrEn^eq}_`V8tLVA!Q{)h z7LNtQg-zJb;Rrc{A|+W1xiciSAH4&z_g#9a@AISmuSloi#N0tTTdD?sKJOxQrz2@! z;X`tV+Fev$X_;wmOsxhKZqJ@jt!y~FZ?_}qa{kX6m9Uv3ii$@mmMji&uWVu19RD3n zyyDd_)tplM?fvff6T+cl7nN3J^!v+>JyV-a`$ya@ChluN$&|B5;FWN|Q1K*wiIfKaV1`TE<6-jMr*=^SP5$?Gu|q9Z7yJ%8Q#u!m(aBt1jW6b*Y3 zwOo2QFJ@USv)poOHMq;YRewx$UqT7!gx`_YUI}Fv&U(Q_RsCP5dPbhaE zRTqQX3w!R7*rVD%uClUMTRDaB*Z(1kQ?nHR!46@7uKk683^(B&&|L}si%DMl3BqBT z_epr<^0399w}Mlft~WiKZaOdzwteM?M#$MG+LSffeZqx;(h_TI*HE;7)E$+HyOgJ5 ztviRCb*l#7TE)|b{_U>pQ`B|c)iex7+Pxgmm32of-5)T)c1 zz=7+7@j7G9e`=!tRtxEn0D{5cb0HH*?Y(mTWu{#%E(E+t(I-tgSd72R73r~J1OHjr zWl)W*@bA_bcIOoo0`F9jB_YN+q4-g}$M$3S8MFuqe-FMyc$Tr3He(z7;M`?yERWN_ zaYGRGo!Z|WH*I(YhA>2yy0#`{`Xo@_EG6H>Z^>$pyqSNewDivHc$iuPi7AkMv}??nmvU3@4JVZfpDJPKf8iUNkz8*mEQ^8VCnO= z=T=N_P0Fi7Ik$G~Xcm%tcE4iMolYEux$MDWlszN8+aXO0bLP}Z-|^fmuLQ&eb8b!U zB*;>JJ91M|Q3cA38@*HR95dk-L4A-^en%-^yy{cUcd1`2_T}+IQQbNYav#jT{ql!B z>26o%TzB(u>atkovsYxrmf}t*Uu2h$rsw9G0TG>*26^2#C_%&giS;M;r+P(*-tLX; za2l#&P;hjao~cV5nEQ_Z+35%Q_P49{__lR(#6+VBdp6-s=3!`*M+>}cW?uu>PBG3M z(6bF=*4;qxjWn{%dBY9*LYH}DsX^TXCT!8!0WlmMXXa0IEB<8@%p_Kn2n{>CM-Dj2 zV9-<5oEE;RPX&Jw;O{>BzHF5TRyHi6qNKMDIxBSwMle!>Z)gN=@|D z&Z5B^URExb-)x;L{67J@&LlH8_GpNsu8AZTmvSCSiRldrL)0F5o3JktgQt|r2%aOd zP4_aQ?RRMCbSVpzYcdyzkh{iQkt>wIN{(K|P5m^3Mk3k+&}Dt@+eTLUIynZWv66Xb$tA@!Qkz4m zld-DP%B!-dyFkoIhKuPuEhAOUj2Mr9rd4ja8N;uq>1;_c(CI*h`nCPl*_|24_(6mG z8DzFh)@%M|zu1L?EC#tppxIQlUMAVs?V~NHLr}a3*6HLFDTaxFa^~a=)S-7xQgaLp z5%%C)Jd(~>df&QYCh>z7_(P1Qec2uW2USO!4R#N5i+(GiMo+<4s2jtb3?J)Z)Jr|O z_}fRrKh?vgt;JFd_Z(c2FthUyM;Ml_{<;zz?1O&FfFA!+{~aH6Tsc6@5LbUOtO}e0 zNFW(VNIe(vda_@}X$UlPzy~X0sTV~7pZri9@7Bc@*SDT-HAtB@D~tznJX2D9xy2aZ zjHZD!Crfl)Gu;Uz8|=r#5;AqcVS~b1QKDQk0v{fpo793W@lq+eSWU>smSA#rTX$OL z{P!&sw4ov@u*M>x&oa2G89EU)>M!r4GEkV!=k~qNUGVF_Jna=9BwGBTJ|8*@R>3-e zn!s_b=tTr7jt?rarr}X;uTP#f4`20`5+f`o$=Kalul-DSw$*G}@@8M%Qa_Q0Qv`u~h@I)AuFyp2jm98NLTF&a%eX0K#>M2v0-jMr4;r40lM zK&lGDO~0qQ6MDLGn3BBx9J9JcRu=dZu(r}g_ns=|Jg&<@t?HIpM? zS}OXqf8uTQd^3GwRrAc$g@*mE$vZv4)VQc`q{giL!nFTdvRdzr^FbPawn?+z&GjS@ z%*{~cO<(@PmF`Godw``7Yb)O9>W0s9lO>_y9a6|GehkqK|I^SZlD5lNVGmFr=?%Qf zpwh@abB~evNqLI0z}HbLQ$X;{fXreQ_kzXiTnC`P{oE1;-R$A(Zy8YL5>mKQu4U4aPvZeOb|Dm zn~RGA1Xm?@ZFoA|^A(`cJt4s{0vPP~efw@X~c>>D1oB?^meOj}Ng?TBbig}6wNL3YVHDE!XphoWo;2wzg6xQkOGb7S{^81gZ&LjQmomRI`LkrS zm+6dzhuD=>fHo3NH4ZY2o4&|R;YN6GW7nnC=8GBI4cEl>q>wO+?Vc}JjCJhNAib6S z4+dF(>ib}2-`jt#@YelbdIOIl{NcZ6VUqu|Ln&ZhgiWVzf}%s?6cd!3#$C7zkT& zQmXJ%&#c6}2sRvD?{wMnV_d0&6ICEC8UzHIq>O~98o)jKdr@9bbQa|ho8vO$?R|UM z$KqG<+D{2>JpAzYrQ1J6%))8C?su|T!SkH0fih&yIK<%_2wEcsoY9gMOe}*cOyB&A&z>0?27hFm3iqFKB2PKFZ!md$*fXX@sasCy(CM0Y@a)>~i;HWWW&~ zEFW4$)Js`pkDFn5X7)29@3Yyj@%gB5KiUKMI}x{WJaJLN!z!epnrjGTqu568E=LM* zv(e3oi_ar%yKFll96cC(S}N`(PpDUE5|szIawYxEUvMo^kGX}! zqVO=kNV#NgGQ^k{lI)k4xz1JWY@7xNq!Mvs&eP`#SLlG2{jDB$D?yD>7pYo5xXONnuFn333e)cKx3?gD{j4RpW0nfA3S? zFpjKYhTgX+@E~uwKOYDBGyAVzfpB%JlRn(~fFf2jJ?22*9^(7soBZmMpSD z4+CF6b5R<23``k-H?=tySqn_qdshxK+?GQ3C&&E(Ru^|tlhXyN39Wasg60*co|jv6 zonaqWlO=i_<`rNTbyU_Q-we;`?njf#2LTYbF+{7{RXApa+3MRLF5K-oU+bH9Hk>$o zkt=&T*g+>)corGSGY5H$j4obxnGFA%xtlIzw&fV`zv9lemMivGti_<;IEprRU+RD%(LUG;TNPH$2a=;YZ`eFrXuCEI{H(oG|WA&TB`0sOt$pT1OYBbRpyFRVb@Z;b*6{@%ACw zexP49neO39?P6`!4DQz6y? zmm!OOS)sJdf`D1nDHGsP*{^D+FTBAOi|@{x_;*;XOVI;sHvP1fLY}c&BeU}x)KkR1 zE}nk$;a;Ykx=yIyfP0s9EZn90iN>}1zE4KFr<$=pw)%rsP9?SOxC8`jSi{GBD>I5d zanpRInC4{mf+u4?V3>a(8I`XLAR%x~Bmw z?}aa3p5~Bg1(mCEGbWw-S8-fS3$$E+INqL+Vz8d}aD&Oe~A98B}UeOz)Q55+P#OEDQvE#VV zgdA*q{g~SJCm)=cy`8OilNEtrpP%GU(LN`S1Jgvf(3kIhJgWD}#_6&>C{okw6G5=H zD+g?Q*jOQ+27HmxLWiM}1)1Flw_Hi?X6#LdXQ67VlhrR`Gf0MeybebTNMZmP6ed}z*k&c*&TD~PFM9rRXM zp+;NQ4c*RYPMj!1${H}`HP<+O@4^pVr&e@5+i0p_F~i#OR|-t7656gX_M8#+B5ZmI zsTzl^V^8lD)DK_I*9)<_T)$q0T6}HE?6wZiSf9K(U7VPUYw$ry&Pp7ZfTuV9HJ=H3 z#?x3Mx7_6E`TRZDlW=n@OX15ZD_8ut=@nvU8iJVh&mOBnTmZv?u?0idfE08=A6Qv# z{;90m#d+Z-*T0WZ%$PK7;QOEYvs3nRM6D5f9g)k@hlxpvV-2_Xw>?R+l7I`m&X*6? z{6jNy`p}c<23sWLl=kqZIvvF)ya2=RB>Z0sF@n>GY1yqmGT<_rUgU`WVnHbP*ZsMg zT>9~@^eDwFuEet5)E8Hb1AbIh>d%uyDgyW#bHIYJ@tvV{b1q0Dmv5eBA0rD%=3vc} z)}{L9MK0itM2FKsD!rWck50H4jshqYz?tW}(f%s(Q!Rdtf7pm7KNNZ|(t16)P_;Gj z#WVLLi}K{!i+NXWo3Al3HvHmzt0UPL()Er1*kAz;uYPqRM;%r$cCgNqdTJ~A>mNk5 zYG>4B)OL|;-b~L#L2X6z{%0(`W1{@Ecti{2NuvHAgWeHsK$*{d>h;MrFM38F3NJQl z5I7)k7&Q7*>tIyXC<&wpL=kxsZKdTBIqc8^A$Qa?aGs!&n&KKBeo-%vr_UTmsa^1d zCpV=)+eXN)swa?Ml&1M zZqe^xKX*7&IKlUc+8bpx)5Wd(Ht*u+f3ydgHjpiUl*@3yp`^cF{BY>i*=feEDlLIy z!Ywdv(1{AB)R!I}4QnOcZpZgw)##2+oZgTrEt2eFwW8n;{AdwN0MKG2_;B38hpmKl zP&dPZhit{;q{s66Ga4(#f+d@4evPXJW${YTH?KFda|Y^Kqi>Z76G-gH&+#Vrzu}j! zHC(H)8vZ7tbqvJv=~Dg}K?7+BHE31bW+RE0FCd=mayiol6<8kC%cVj>m!I9QxW1b1 znF(oUs!Ju6PhFKz#hn>Nbtjj@Ka^_LF;T&!>F5RH`U^>M=#|)Q$<#u0K!-~xwK{x~ z3R#!S)$udjy-TFT=e;)1^Ywy=_o$2j%XZ|-?3r8Bi8nX47er=HVgrPKvj|%MScJ{n z)6J9-wt$qs-9xlS%}EpG%8zoazp6b_!}Gxz$DKCV@a?_T;aWdjp6%>P<+`%SV%>YO z1FzjZkni9ij8S{bf_iP>I4V_?2HSUkJjlY-3guS1)_9$GeU56@ROXp)sU{91x%#Fo z#+G{wu^*zpiR>BM(z$v9bS8e#lS_n3yUg33(G5slK*rCF!ENT|9h^uRD1A?TSd%~} z(he-^=T4y?7IEr^p@`l7M-Ds6ysSO5Ivbu4K{{r&*vE91CG)-+&`WEO2^1hI0zz>V zdqlD!kdNMF)(J_!23URYzsw8a#2dS&_@R~SFYbeGjxiVD8$v){D52REZ#@i}V)tj@ zB>Xi{)DFbo%KgH)I^S>vZwIhFkYSql2}Q>tRtVJe-9r7=(c2F^T&g{#VjKVj^_O$Hm|rgeBzC+yUeS#xbjc(<&3VBIcuE- zJI+PKuF1b?2=quw1J`?!i!ns|FZ(m@4~h(J>yF4OQo|b-Rc=Xy zFLM4_{IP1sv*q{vp=Pg}x4{-WI^B+H5<_y*g4l}490E!0%f2j)uph%hklcQGx$77^ z9=Ehm*neq@n45aWmw5CeE+fLseCWP$O$!hX^2t)~TXN4S#t+pJr&p~rr_GXhC*~df zf3g8lXB+=+0@TxsiarITdP;9*-$Clj3*V?rqkKP`$t`5qu$t>2DU^ah?nN=x7C7=g zCC(g3=yWW-uz$FE#gzq)Dfd?`QOZk9tu}&g+0Syb!&J&gv(MQ!hX#sWy?+?$*LjVe zf5b=INStQ(J-#uePv+AFoe8CRd33S1rB_f-aDyVeUG=CxQUKWF!?NYQ>C# F{ukY_Is13x102Yx0&UK%Z6pU)j+7=QNgK?pxd zqWcfhl9UVsPRfj1GoL;`ubFjqqNG)P`s&=kNYEHB`qt0Qbia~Wr{%WwJd5Rjb$88txDVmvaWV}AT#u+LQqx1_U|wr36UMJaQpyDI`=j8Q zc0b52{PbEz_nvUw!BptO>V=!-XFg)YW0$oRf!VS(YqSbode?$^EpHyOMh8X<=n;vS ze_z>s{HW<5`26u1Y>N@3LFE|%fnMjXNG1120i;QM)~Vl$pxq4``9gOjjep|myd`jU zRT>PWP){ogwQ77|Mi{xOiC5(GzIPHFnI#aJ%u5bdl6taQN2`+2S&gS zsdm0J&lOJS;6WeI;>j5FdMKN!^AlV;K9}YV^*6r%9r%FK_!u~%x$dM-Xlgz7KAwhH zX$*R0la&Pm15EiAI=lk^v=*)u7YqKDHCAwgFg$IGBHPm*C!ZIoo%H9qF^0NKECp

-Ls|6`&@u;})$TIY4@nJd*JQSDd<^^G)n1Gb^tKH6 z2jMy>O93&e2|ApUAV^IkDowmA^gd@j#}yI0qZ`hjyrdC3$~ z@lXdnd@1IqV%7KQU4>kCKbc%e10A2Fmm^02mmaxxfAA~W@Q!V^6btXPk9$tkho4hx zjQP#mh-=zbAeE7gUpm;8`bS`)qM)FTjE);Di9>>{cIO@Gvy*y*$VEl+?t#HsmdVY` zNYLg!e|Uy;42xKM`*^{0eL9otybn88`OCz?H4u+nG~TKzB#9LM5;f zLjB|0H)(0>nS8nvOZg%QnoTW-F?rT8Nu7CBNuhiZ^B=B1%(cFM1B2t?NSnzpiT z1isW4=te@{;KeLhTh|b7xAfxlaALdJ?7-NLOC@PF?lnwLrEv3i zEP>CPUBFXsMtZM(+HMh|`G7M6>E;-~uhZfNK2vD!^=dIA6auWmnfD+_v00s_w@!BW zSf*u*OC%-$q?=~6dVYd_G<(2lLt0rb7$^+;FzN3Vj%%$i<4q@N|8{r{A?9u`BW4eg zc{`celufLwOFLb`9ctqJ?Yt7g{Z`wE_$`STKPGdAeWTg=e3F5#dZqSn={}oTb+VTS zy02bO!Yk6*LCD&c=Df^^)Bg0V*u0A&8LdSY?){chHlKSu)sL*Ba}(ug-KptrJf1}0 za9NMtVe=Gi>+T4Dr!nOM$M3v`^%(l@w={g$v)y)X;=266aJ|c_qk%})AlMC$y3*~0 zU!in>XmHOq4nxnMUCJr1cnOl7th!`gpN%0z+6R_lx4?*exVdgkVmr@7?_1Vo zSfis$PKVd%DjoI;s)-HrDb6rY=nzF~7_$mT**42p$`8IGURtj27E2!P!|v(bIpE;z zbo1}nM7;mzoV{1%Y3Y9PqI0_B5@IZ44cxM(VnsqFFAzk`Z(cR$Goct`%g)pcZpI_# zz+uTb{e8B#oK&DWBR!y8@WY%S;+bpNIeFtc-Bp)wj5mLT%x?W2-?dVE;+XgQ=E6vf zRgT`~GllQ1xR08W?25wa6W0bu@$KKB@y4a+y17|*oeo?4l~1-5>zTp?xdVWbsl~Z! z9P!jv|NAS4quJ43V}13cv^&uw%jKlKoVF;0U}{fbXtad$N;z@cdw5vkWb1QO>C!SF z=s42(bukU!i#maA=kMi&hSNm$`)1EAw$FBN1WgN)PL|Z6m;C5cPxCt4aB7Z;Z;Ug( zMVa+8Yl3w8w7iLU7kCBYOIi;h_c-{5&p}PkPBC}M9=u4gjepSfE)`ulSRUPAHt&M7 zCVdt(6jl)&+R~7R^Qkv$npe8Y$*Kxy*zc*7tM0e65gpwR*=*La&R1hup6^1^+A$6G z6N#4$hVWF7q?T(27yRR1j)e1GzErQF*58GNOI$UW>V(`AfJanyqW+T#5HcxmWeP?s@)yTx~y)fx=URXOUfkEIWZ*&A1;^Oj4GN-9*7~kLdL-j>=y-_y- zSc=W(kL1c8b;|4vMSrahi8p}ygV_8(pJ;|F(ea5lAHFVrIO#jLq&UdP)SU^BRua7K zOISL9*1@n8_YQ1}OrkG}vzK4GsBBC{mqZ7au}^`uJ3rikl~=<;r4gg|Q}JZ&4jcbn>9pgWL{|GwcltBpPi z`pSyNJ|br>-^IG48)spNzfzx2kv;@0pdXD_Vy5HrI%NEfHFlQ$Xr3a1R?w7>C(&@71c}GOWO^m26Fls0=apG#f5Hxb z-}3qnEr`Ixw~`IlnN8*W?*x4D zP(66;0Qcev|Pv{@2_>a($W#6Ty09uRyL@KyVyw_bocL=@GiCk!oELML)AF4Yc6qoxC~|!Ud7CK_XTp z5L@2PG%(*HUW8GxBVNrwhFQ5hSRi3(d3#lA0u@RE6)wXVPU8*Ry}@1e)=2Y2;z&MA zp3@l!N6Jhj6Kl}m?kmR07ABUh)r%wMxZ({$tq^JYPrluFeQ3^zSC3ftor-9*VWzu( zB`GJyOv1xeh!v=|8z@z$>t;K{@Lx~t`i(cq3a8kal{Q>!6MD zxKiJyOQ{wFV}Xzi*g%n3=FUlh!2FyBCMM)AS+NA*|Ma<_@GR^6hS<11**VDq<1B%j z>!&gl?befQo{U5ex2kqk_aqZhI7e16YBtIO3LJ}xizMJA?OC)c%|64I!j)E;KIm7D z1rZHU$%0+=1?X0038L%&unzpgNNeC@V$VDcVW2l4DNc%nZQOX?2KlX zy-!X7Te8NYM4wa?uJRb`%;8;jPT079!9Eeu2DQ!iV)i^>As_@s5AhxcDYKh9qBnIlOxEvnCO35lO%u${X%7IrUZYTW60KLw6bnTvSPn9z5_|I5UxHKD;^$~%{Mmv2?}aVxL%XVwwXXmoGtZCiLD)G@vsg8z2US~ce;NN|X0P$T+A^~b;H!w|40;94_#RF0xz?532B~%I zu*Di``(SLDWS3Ahu|0m=Azq|m>;g&SyJN$rF6k_nFbq8uWPXsfkb_GB^FV>L6PKRWL=xQsG*nv!KBOPzm17(Epw$TF<^~ zl!hmYw913|YtW+1o-d*rGWQq(_JTE?a#6O=b-NW zMNz;u@18ffs;I_W2t$HjV+=1gq&0cZB{SKti%z{0h*b_Ar%?1|V-A;e>PRk-%8no6SZ=OI)xq(-Z`4ryD8T-1O5 zrRkhCJkikf?1Wz4enFRg<>;O7{<%UO4fqyqBzBo+QD4fco}K0Iu^j=(l@Zw_C(lKe zoDrVdr2{Y`{xNzph8S<33Lq!iRrjLFy^(y)jsj4ZDP1J}trA{}5fDEw>Z(211M9?p zWA$iV1w-DyQry9+uwxL~$KGJ3S4t7i!b3`JIRkCJNAh3c(k>LN_QOp{$s0-ol+Ipx zx<#%9vJ+#B=^NZ6q77~12P`*e8yXZSND;g-jJua!J6wtv^6}R!QLC3ju6t@9zvz7>g&J0MVW8I z&}k~;B7UU{QfUn-Fv-K1Ok=}{I41+7JD`@463&%QQ2ohV1NFx5iFx{=m0uVEcCC?s zI!lAr=WbelB~tN0c%}B&tnju7)X4-lr5eHDnOPK@8x05*3c&^9sax=0o>mhbtmLb#?b1jX@kqN4_~;|9-OtWk zdwJ40@ae=VWnlRpxKW_pbbb7ItvNarx*y8I-AKI3A-1DuSjwHpu2mjV;7RYRS+qS& zD2mxwJ%{4$8I*T8h-6Vs9D;lb)j#cqe8gy_csoD|GkIS~b#a*;nsbRI0VIo7q{#07 zNL4M(%ru|^UEeE035a_#TP1jEdK4W$fN+ys61Dh4xW}O|GKdMa_}BuaUG6M)kf!nhb&A0_p<_)Bro* zOQz9*oUXSSF&T9txwN*8H06yPE{N1qFIkdK2hWky)-f|5{lammbS4!=!@K?YOC1j5 z_O7hFI6sfM+--TRErd!ZoHl==TSfyKt?`!PI3yl-Kmfw)<#t0p@Le@7#(Q4*Jsr~VkAy1sR@jh2@Z!!AzAkN zUp%cP%_34WybDK947KombAU z$P{U1v$F>!8;m`XE*W|J8s#^KXWMZK;+*#|@Qg$gQf+!QJZ+C)SHKU>Nh}_It&_Xt zVcJv4x?hmKJisMYAi**EHIjMObg5}X7X8$-n>Bfj*8!Kr%*9xX2){*@x^j`LL7q|4 zs?AMa$?FP6L%g>&)U0qt{_=K85|n*O@LBz6f!=pkyGLvr#le{@Mq$d20W9OkdHutY)ul94=jRkqjk>T4*6QIFY zK0W2y>gi;z4)0PdTvgo1?Z-Y$Fna7~)jqJ5z|-InOIyW8V|Ct%^RUcyF>@P*fj;B4 zl8zc|Q>H{++WcT}4fX!C&^Ae%l{tD`R)qsF6mMD=YME8fblw)b%{nKzRlt2&wJcRF zx2$z7(GQbS;EnsaN>BqE23@ zRXRc@fdTV)Y13TUVgCwF?sNwUu|h-azSz5#x*LkJG9yMI_{P!QT{LDzW8lv_IC$Q; z;YQ-LZY`<)KsQ`}#yO&ABk9{OV5=*D&Q73NrwXp4ALicKZ7e#+mylR*07&b|^phsJ zFi_ioiI47A8ukaCGhcOPv~d2Ag>XQU1~WwaThBK8SPbW_o3~oLeb!L$DqDnorxXp< zQ>e#)1ltD8r^Elk_=5$A|1f?OI5`NkFE~Gd1S54wh|JyHdX@SMcoe#Orhk5BbSIwJ zXczr1J)1}v+5k!L{**KB;)!hbU>WWN%22xuG&m)SEVm6Y7`qOln-MnE$x=tu@`is) zG{q6QjY@K3ltON4DF(RJ2ML19Sx5!J0W)T4VPM%89_;K5XUG%L{s(rO^ z&C7Y+@~g9r<_B}X_=w2AG4y*yNDPOotXo*jyD8#-%l9>QeaF>jCbFiQ9=yJb%#r2( zfU@I1x3wLNs@k8cb^;-|*V62O%rjd7u0FaPO0e45;|HoAcmqmTgzS%?dg7;;_f3Ya zeSsB{AR_LSMRk`;#Wgt^kg7#~Ua^{FQl2YXc=N&ImspnVsLfSf>># zz&VfLaGV$WEB+k9r#|}#+ARL+oq=vK817ZDn4>_e62u7}@^m#c8rpd3ex=exPvK8w z($x<`K4~73nNeD8wIY$}IlCJD_eZaa#|2hR;WQfS@*p4y`T0vzDApwzc5Tzx^fUX* zJ;G#SMD7#=6jSz7j^rpz1y-L(!P(JBfj}*aRDs_#GO-rg#x$R7aW`GxY%WMpM92a9(B2a{k z0&yV36se1j%1NU~@q|KAd3}yEpFs9`T^Upnmn-&lK^kwyL5m)mhD6EqXkeGjZc#S3 z@W%L29yZZ(FRiTU_(V0jAjX6kW7*9HLbkNAl6xO-YOVX5imR`jU=k)iW2@xz7|K?= znU2GoLsXR*_4}H=J&z^N2rMRBA_YHfl;DtRywll?&3Q42Dk*{2s?@^R3~t_Zs=4vv z_20-&x#7sVrv=x#mYDe1O3llS3f%pb2?@L$1x3UBF$&gqCAu2@w!wFO)qHg@cD3TG z`ZTtk)F}_BFh#Dqu}vI2X#pJqY2D;6*u$2pokpn0RkFIBDnSlV7gtmkB6eyfi$i6; zfj%SsaZiY+D$Zr#+kOB^#9*kB6)qf@Z|Q|5MXh@bC@$`vlp>P$c^*go$HQ^zK1kv_ z@evJWiphhC#43O*V{xOi7 zKtZje4JhegF^KLvz+p}FN1UaY1Q~OKA)mmKa5E8{-1cQOR^?ZNz~j6L#*3*dGH3Fd zXz7prMiraNttfj_2I&b4L9x4 zr-}K3xNw>D_5F$&;H2V-zDW}Kql&FBO^lirU(gk%;NNHfqG;}Ag3^dx+aCuzEyz1hkcVd7#$3|2Bo(>$Kz?L0n$db*OkQm_<0y&yGcC~^>Mhrh?VqnL1}r#kV!-%u1% z8)3dDn~s|mF{aOG2GrT#3nf(3E8R{L*rcx@iR&E+1^l;eX-usPq&7w$Gckku!?IRN z;^h9ePiL!wB;GA?-N&b~y^mcVEJCnVGQZPS35hx%j68tre4z)Bn1!CuGLDDgo^ZuFQnJUFNoko>WwoF zaJ?y&HJXc}Aj(-w5;*kV)0ckX#&F=t@ee;GLSz%Q|-DWdOELjw(qA5N~ei*8hwUF>=XzZ@&PzB0gCI0l~KPojMbJT6Xw zk)GNc_{?Sg#oEzUVR?Qy6MN+V#brq?oS%2-qQ|UvCQOujkHbF#d^MekXj^e4=h9If)G(7WuiQwGh?EW1URc9D}U? zOCIju`nHa(63&SsCLNO#nir{=u=vyn_V$Cs=P+8rwm0QNi$!2M{szKAL@5x20Lhns z2xwt1n8SyiW%(a1K(`i&4qKVq6$!3Y3yLa2tuP#D!yJ)#|0c;!*B=$C8nP*F0>szJ zf%zXYBF{Ju--!@j8#B0EZ`kbS;7zrWhUVKY2Q<`RvU*-&2ecDIQd|hg0+ zl7*-6^3o0*B?|0ajR*d2|0&lXT(aU6@9+@M10%6)oRtD`DPl6&XP5*o;Gk|d?+(05 zC7$o%qe3AcBxrEt3=$_>ih39<yHx!Ysk#A9O^YWu&}UK4@F;0Gpz zu-kM7x)hG@NUNFrT=fV{C5r!`EX)3KbJ~+tpTK4u=>G~8_Api8Cy}QOUQhU2GcQRe zOm%i{=!@UIAdm-<{`C_b+{VFR?1V{AAr0Bn?P=)s5)3OD8Z1mNJuBuFo$v|RdAXCn z>=XYkJij!OsR_okzxdbV>Q{4sR-T_oUdZ+`WcRmn^70uro6gis^Yog;YY4MO>k!Zh z<16CoVgeN86-1GNWfjz{hxQ4wuLNS|@vu?qtpN4=V>RF~&?FU;XO(AF$To7MDWS)3 ztx>>2v!1Skt+4C>b5HhA>^S%`Su z%}NJ+%_l^?DzHm~OF-)r#egrr=REvGJTrF%XIHOYu$j+e-j0s^@bqN%J4I=@PXM?C z$PJ>Gwk&jTGgPsD0w_*hOO2pvJXpxf&VKYYMt2lV6bPrb#S$J)=9^;ofkS1)n2k!@ z7ad&tP^!TLV#mQ#+SKfTY#B4e$ui$w_ls{`4au)S58k?kWburL@b%)zT4wgBR0e72 zW0i}~>kVb)@zd{7b{!;UW;gWF(|GJWayg=5;iPw}4Q!ZTYP;EvhZ)_rBFQhOg5Jf7 z{Vw{WbkmXtY1rIW<;U<^(fcgPBH^+Ye9&mzA^4WtC>sZqNgFb*Nis`#2 zbG4&*&q^Umkl5nUlbwV<8~rJ?WFXcu(YHCL z{%!LZ!c@O|@A3YbH8{K`q-dX{IY$XLwEBzwMNA80df|8q>N8#gTeDNK^#gVsA~h_5 z2cBaa9aPO*__K*Oh3;+$LJ@w0f`z{65`_F=n;Eaf#4#`I4ys>bQ7AuFPiz60a|q-d zI+7Cf6Rq7R=xhx77#GdBBRQ@G_Kw10DFGyJ1MfqiWr>PZTOyOj{G0EYu|%GjDGv<8 zCG;vv$7hTd`|%JAYZ-+Pr@FoxYR^*Btv+LQqD0)*F9=oY|Dm0sw$loSKW+6d6pIc zAeKKN+_7+3|*J|?L0&E>)i*0hZLTOh+8~^S9S-NM@ z@7=)Y1?OY~8$i-2T|d=r*gYtn#J)z^GydYv^Ak&Y%_QGO#&EL=N00lRoY##OHWT{JCL}H>r=~wZhhl4dX*#X~qdLtgpDiFac)oIxG+mD3xZwc;f_yRx z&t|=kKV`fg^V+arGB0=ALybW>tNjvWi$&arauSAel&n)_VV%zBa5MI21B#f`K=L*& zf0K2y-_9y1@!-6bQ>m{DsqrEOKmsb&S;hFfO12LS73uLh!G@-c0L5U3E5I4LTaoRV zh&d$8x%S&fwcPyZ@sGe#uu=y85cB%!i?k2kS7>TjYTVgR*Wx4QXX*7}2A5@ZK;pz9 z6|BRKpHO+1hl3}c^zAPnZS5c4Q8n%dV`OYMPooZ2-X6{xJY#q71URLp$Ft;(eDA4{ zW!9_PdQ(?@p-)dkm+{O0!=i4Z7YY0?6&(McT!fGuTQH-T&eB%0-9pA;u+A%yVdDk( zPce|5E6n#~a-SIGHKR6g6*pq(XtdN=b#{?wS|p8aS^OX2?` zB=ONGg3)A5lVe0Yd=jOek(#|x!$>5px!kcr^ewdMI_;pIaAM-=b{u8#2pcU+9Nz+P z6!e~q7ls5K$e1yE?rGry z6`-@ePEm@(k#vXG;fR>5uO#b(-^sl(PY4k68}OD$Girgr0XVLWrxtvFJ%@{qa?uFfz5eyA{x)9XL?CEy!x>b&P+TrU`f&f%MZGSzzQk_ z71Z(q69rb^$S#YAf&5`@J5x5oVX*Owl>}FjjUrcQCSKKwT?n@xLFhXu8tD-SiKRan z7HuMaBjQoIUEki%1?DPkNV(KISoJTkXPkxfD7NzXZN*~4i7$TLEBGfmZC)$`>M0b* z;OJ((az$PMf-|TwTa-F@D(fjC2nGA16>Op@$Y9pc)~v~_J>yQLCjgNaQ&Tv{EKlwHD3* z&nN+&)N1z#hu?!uBIY>evHgCSmlX0;qQ4QEtHF|N+m;o#MBcBzi@Tk}@%i-Dr&Ls_ zJqSvp*>;%QSOFerI17%vkFI~Cpb6TM`*O@}${&4>6VyLqZgAL)Q5qgp(5lAwaPb7r zsGbD8LnYu8&s~^(RO<194GK;Xb!5D^&fFOcx|NIuI0|71Jh#Hq1c&CkrNvX*+*gYI zKeQgRHB+(V^&gVmzes1%-p_qxs^a~qW?4b#=6e8ig2>&H91@6Dpnl))e*r)3L&RJb zQioh7FV=~Z;gcEbUdCRuGy_$GA@x>49XFs_RBQiLJ;Kpe-ZiKlF|gwo&&AO7^MiUQHSB3r?6@lolD*#<$NK#+H7vn9xJ`ejl$!;-0%yvc=rghr{MQ5(L;PFQ^s3 z9Z?t&gvV3$p~kd}V4fH@v_ZsOsxm??sPucdcLF+C3PfP;5Cl<@A?Ss;Y_2+@AsZl@ zOJW*qd{I%sd51yE7G-$R7fo-5NgnvF2x=&pssw%Wcyt7U$fQ}aeQFuuw{_1%K;WlP znBU$|ZdMaQLU&ccK=$|?SbbAyv4U#STOMtnXkA}^f9mU+x8&t>6e-7B3$#( z0IO%M?W^JDoEv$ilXv3dG`%J4#Z=EowOUSr?EzUW=LkUEhNjUD^iSy=3TC#z+e)ri z=x-PmP??w()Sr6rtBWGH9!QE(>yejwb=$7n#Hn6 zvXD(zf5}C@w`Mc8bq)BS2ue(3A_~!StblM(4ymz~sWJ#!SKlWt{M?8Djqj-2A9*OvE zsQ4pGg9Z8m!ly64=34g^y?QPwQEr$IeRp7^I|M}=XiOEG`?YaA=fMG_db3z=@Skvy zojlWn`98v2tljKZiS&UtO;AQ93EpqKOV9ZTpKIo8sE7V79$GkWN}I0)eN~yZ&xN zDqp)fX6DzD|3}s@(TwpG{UQEo|F4PrTAwXSCve7?UnTz$9$g_C7*VT&Oei!Frt!Hh z7XgSsU(dXMJMt6~BHK5O)P2VT7X&nV33#;1&T!J%Z#9OL`dxpu%^gXXZ=R6i$6-J6 zwrkzJYyAFI6}Y4PZ!H0l?LR|+qQU=C7XP1>2eAKdHUoy@-<*Z1nNX$vf7{Vg#OG?4 z=i@1L=+~FJLRRncxL?tQ0I-i?NrCiM>vnt`8vT3sPZP4(r^|YrFXJCn@{eh!uf}+1 z+gG3$2%iK`= zo{kG*(A|iU^MK>0w6F~D!n;k1%)|?=D2WC*?cGjfd}Kxye>^yRUxLQJJYuZs$$^z_ znb|*1+hFRx$p80Fz7d=}v9XtL(f6-*06-SFX3r7SWKD$&kv3+69-=z0T#fIHc=f>K3kuCHt z9?(x}ZrJ;-o70^NICT{*$f`dVd~fC?jU3593in@{rQK@OnRKd}W_d9r(y#{VKD3r^ zCxVOzB1GSH@T`ImdBcxpM98iuWg@@eN*auNzd&uOO6dt}WOT<40a0#V%rEV&M0=6= zJfnf$M8BeSh0zHn_r?qNLE3Lic8R7Mf1``#S>V|&<~GW^4_`#0IqXsQ`C-BnpGboD zjx<`M8s+{?ggENQ!uGKwKHSc9Di1G`EW=B_d`rG!_XXJdPMRTy_6KCMy#Uf}&C`CZ zuJPUXnvaZ$Btf$VTnx}b!R)uIAC)=WSmcx+K?$%ymm7?9y^>O1g<@s?r`O)vGm#yr z(uhZXllv_1Ox+gqXsqXg{gL<1sDlfdT&39S;xg1OHheS|dg6GLnVG8u@*^dATPxPr z-mt9ElV=eEarC)dSNH<3YI%3PzqnSJ34b6}Z#byXY;<7e+IqsMwLMm>yf19GZXx9_lQwj3s9pLxmyN0GIvXz3yaK2!vK5bk> ze!0}%XdHRN+sL4{w&ZP=Q!p@BMaBG7X6MQ*)2Bc6*_)@v9(Tl*_IW|LBrnNYY1!@4 z`om`?^SbF7P6N?)q`l}3XjN4tV=UTYbl!SA&+$NANI^kwJ>5DSS+vmFkb;~PYq8}9 zdRb&=#>oju%3V9KzBu_d8Tszb)3JhB)X@}Tl|}we`?$ZZnMRT3<-;Ay#wc&EP2aRk zgiy7UaU1OJBDB$jTOayl$x6!;!+ZfaV#${Mmy=$0Zf7Y3FDczaQa{<6 zInuhO*t{|&xvO$`AP_enEYCaRmgsK*#DAp*U^441%>QL>HP+SN!_Dihq}oAOSK{sVJOFCFE|(z;mDzFi$U^TDc(DIp4Z;KB{BWbtT0#bKQQM z3@Z;Wt(!n0On@lLB4-QJh^=%CRyGv+A1tmHKIAWs7$b4ia+X=wi0q$MLBQh+AF~wgP{#q74r5Q{GGH>Z?+J3TrX?YTdc{T*S}e(kg8-2l z?u)a}+m_rhK2pQI__&C*BkG;ci?d*(!7Ib6caQeMZD?;C2x_8o&_9hp8+tdmz2Z@J znV#V%SJCv$l~P0r2ng@r(1ZNjbO~2ae~8c3>PQu>*BNEfgsyY`jqk}B+6U*3qufq+A$mp&%H^9Pk6izhN(pN<)z7Po8XTSrrhwOI;SG_Q zX!RzEDDx5xxQlJ+pngV_?jPxb&nR_umbK~v5|dS8g*|RM%%G=~GlM^WfvGpqLYaF~ zJ&B3!Ens5D?I$4Knoa_5K#@37L%9jx@|qp8JX<|swzKj_YKbND%D3R*J592SgKk%! z&XoyVz2K)R*8lo$G`KZ-vxQW(NUqfJE1pf+pkV5iV3S8+7s&oce?#RlOel>cuzp$= zhEd2LapeVs#21Rzx6=xZF@y^aB^09< z;8a6>8_<5cD9-fOz5S+8R$c%Bsf(|0G$zR+%}OjNmmdb)6l98(p*~)@36Q$ILB6G`^H?VY#rHC%!g3q>mXhDduL6bFJ0|JV$xsl!JZq zrog7UT56V}24B5=JR110vFu9KA6G(x*FaaCzue!FGlh#mf-k|#WyvM>{XuoWd%HR+ zL8eN2*7Haz&En|Eh@}(&_h`3i15}`>xcdqK1r!vt%dZbs!yj=`Z0S;FmT|KjsS}=z zHW#wz9bPuF5ARw1&J7u}@}M#&^90`OiH{#xPCXfHAAN>cS`>d@1shZx3_Vs)OJf&Z zV0<#bQ*?J521Z6x4~Xjvv;4Q!*6So+!(ASIG8Uo*Jbqb@y0$XSXP=M}w*9psldq49 zu_O3k69-kH%2mTo$^dDyv*80AN*l8FbbZy_^`toBt=UrPrFBiY z;7gZ*Xg)E+c{`kd)!AtKHmf3k8B);dvLQ_LYK-iArXPlsF7&YWzA7R>sh6#mWA{w} za4C(u!Q8P8PmhM|db4jtWW&N3ViphV5cKF4C+l%fXK+x)x^tot{0>|GzFvvV0I8t7KA zlkwAShEPcw&j8pI0g=O9?WB`hV7Y#M!*DXs97y6Ly$HCDr|tQ*S^6;sXwx_|NKLV+}~+qi(BBki6xe*;(>_Es4!_!VH>`A^%e;KKzkPk1@v?v;HrRpFzA6pTNL z*6|;gLTQcg+*~pPVF-Yzk|GK!W+8Q{A9Vnmk|kQ=w&x`TTD)R>Y<6sShjWi07#y0^ zG1((G)zNW1>+SSeqO08$2`!MK2bpmu?+4F<``cXqaI*Wgj+`2d#WmSh`bwUbCb)+e zPuhn+GhKSmdk9n_*|kQ9uS>cDy2NH7uNx>d6_RQ8NQc+lM9=Z^)wiwUW(3Bmt)Xc| z+0^x!z@!<@;+=Zgw*tY{smJ#d&gi$^NkRq};?>}MyNP&JFJoC_dI6oDsNFI2)Q16< z-!-X|rxiYir~Te}3$fX{<5ydWIO?Bo^xY*f z2FqM?z+j|S>|g!m>Z+i*xl13n@amQ7Ac)mJI;B3%1Xgr{@CZ(~{^oc7zCT&&$UG$8 zX{vo}NO3d2wro7eF+Jm*QRMKY&p}9^a`f{|lBCvnlosy_JV6Vb1MyqZYOOV5GEf9j zqnCSAwKilaf-fG}wNqu*Yp7-TgI5&ZCQFUf_~eA2(NB3Z#OVyX(~;`fm2$h$t#+0* z4|8DkR_-xH+SXvKan_9?ZrsZ++J^N%S^x`0A;0nu`1p=bK0+jaMBw8+1yYsWRQ%4v zt@}Vo?I)|=%M}?v$GN$jE_&xRWnlKX=s82pwR8tex0O*R)#>a@llj|lvsa>*e~=A0 zgAw-@4I){IPt|F;i4zBd0kDXs^Ij*3%+3wV2>Y=}e20E9wLO}fF?qyoz!eUtOEbH7 ze)(ilBG{E&xqH{42D60AWC4L|iCd}zgetio+R-58|BlOQ@MMh`(5NO@M@EWe4UO#6 zc~fTfy;sCj2Px9zwK(^Fwz~uzTLt@9ap5 zBpSx<8Rx!c>c0s%SwZrC`pjJdE{PR-n4Sj|z}G`&?^pOp+v9Nczj1MCvUh2kl@?dl z{IP~LY$7?SQ<#nLU+qP}nR+nwtw%ujBx@_CF zjV{~vJ^y*%nYb}C_kK7L8F^0bvtwsQ=5IY~<=&8}ezT`gEf!t9YwFCc7`FA76@(mn z)+GT+BC+@#!Rx*7Lx#iU9qh>o?NY3zmdfh6xgw#$*kE1HBv)Luro;ApJuE;^Lsf)v zMIyXSZ?gK5J#ieb9@OPMEit30Jx=aI$lh7Fb3al>3$sQ;hMQF1uy~ z%{PAyue(#91eR&fUFB5jPyqp%w>nNi(cyE;Btejnyqpu5KlJa;ldd5o-S?Xth`cT4&3!dKs`L5#w9hqL>)TTebHdZgXk?uK? zxy>0qy3K}YrW~qW8gW0&7{*BP**9N${z)G?V7#LWToGNbf+s)?!c0zM#C}b<7 zrrF+06WeU}beG23`Yei`sH)%b4SQ~0h4@FlxlI4qf-uM0N$~KW7WH_q{bIY{4dT(| zDrZtOo(9)fl$#eZ{hx=)d%dli{iOsbK^+h_vqFuQNL1Ra5YbaZE$AwQm34dPrffn$ z`6t?<8|jSw32zN2N8Y5WBc6K;!b8q63WkIw>E!nOsn>`dF57F=EaR;c8(SHR(Mf4r^@ zm+P31v!0>3?Hg<}99ow(T*%lNY!S|c*6YeH<^Os~J|Ci*mb0VGa_KI(Ea{2j1#gMu ztOLDZ%n;DBiUv#!@edaM8y_Ay1}X2Sc6EQZS5>n z$O=_5Z%}Z#aX(nsGyg?5cHv zMKGx1L$LZKy$qx*yG>i%^V(Q?bW9<`m0jxsjr15+i897nGFXsrBdW5~FQ$goRb_u$ zL2=gfsZc3Pt?hO-_G+kq57pn5lzGy{BMxDJR@c)*zpiqN=ISaRb&VVq*N4?2=Do-% z^RkNW8uU1%V^Nkzqfa<#{yeyETS?h`Q9Anle$!=4 zZ1Zhq@cwZE3LU#^cB3`2Uj6|kw>qxFF?K7;1tPxbM#I2tpXP-j3&hiZ8k<+k~E zgYttjLwH6mii7WQ4Qh?2RrR^8&Wjlm?y(6Jp>lkqY0`-TxkT$4iY_%@vR3$)o(*zp zHSbWRq~Upy?q0+Xas!qmq-_J8!Bv-AH7qx+!3fH!;4rIfuQUmio+%}#w}>N^kKjVU zz>t~k>UC9NaQL)HbbCTmx$e|hdrc4^=D{NbwQP6FH_4EYh=!ksA+&R~e3U8{;#tpy zlWfHXvOYZ94Y)R!)pB^>{LsKHyi%R!=~x!OpAZ$aNO7uNIo zS#kW(f7~6jYD#M9$<8ImDHji-jjhGtu%f)azFBjLK2vXpQ>B|VF;vjrV!nC8XGM&^ zl$t$CDw$B!!^;=(6K$S8i;Sq?#J~_H$3m3}Zi-vxuz z@N7alq^c?31qX>_0-lrO87kmF$%Ly_S!ohByX_Bx{of>~gb6DhB$5F66ERpUn~A57 z0U)x;N zkL%?<9N#JrwFh5k@h&KL9CqhD)6Rj;jNI~|XL$Ir3`(=(8TkO^<9@xCXK0$1Od|Pq zP1!9%n>86l1tf+JVhd0$}r;wUc z@a(GQbfX9u?+*;dMOW#f4OvMP*6v-tV%v>0K2;kB^1KyL9VrgzqN62P_BhwBt`UPD z3Hq0Sr7jiY2%H0(Fv|Ou)`ZD<(H9KPEvJ(!>D_N|GC*fMDI#S_7K1N?ufvI%4bXSB z=x=H~n|Ul3@4dJBQD+>RPCITsdXCh~Z|_exu4ub=yhEL{vA3tGFvZwAzg22h&|<4} z$I2R=2Sj6;eG4mn{A$_Af)0p#8m<~a>-}~)+1Y^y+HW2mCaQYgTNUZ=WSxj3 z3s62w9*ug33y#a|KNQ~P8Dr&6V-1j|L8ESL@=&=4_Tt5 zTF(op@g!T!& zd9yVVGn_4#xQvuh3=9}!xV#zpZtqra64*z7!@-tyBX?~Q$@V{c6>O7UX`J3TO2e@G z=eQwu#Gs1OnA?Of{Nl)BT4tR==QraYX-FuSnh|=>kXz?qe+>bhpG)kmHA{0{1U}>J zwzL*egjxLL0jAbp;}4Yb1RYvT!B?u;{162TJA%me@M&vD0{r)DNy;5T!g#e zUS(p^c^QLYtqp0(kd!P5%;02jY1VmTj6laGcELkE+jy<)N}`9{lrb4=@o9m#7f>~a zwvzYufYTBRz0#S5CPHr}Qo`U3Xd-)j{&qvjjbSY{op(TZmJ%v5AIvCDLomkR6}-z_ zgBe2J3)!;}L^r=H&8<&r9e=r}zZr^fGPjFG^x^xr3m(9wZ~sO7gU=7E~8ukQ>*gky7^E z1HCA^!v2V^Uxo&poN;qTWXxaL^y)q~Dxs{AlJZyzD4;s&EvwdaXC1E>FGZwFz?-$q zCyc8e2%EL&$ZT5{tf2%hmlRxl8tFga!DT!_nyUjAuXv(!;mmYX_0ilm5z8(z*2Bd5 zY*(>lRy*F6Ud!Uva@-#6QT^z4M*ZcR#8@omgUMvElu9Z=u&Th5u~{iUDsPd0WJlMvO{#iJr@Jr>R>Up-c}S}8*EJ(;=1r!U!# zc3iJgc9b;Gc4GZtOG(joS{?i4qJmp8(wEsv3N z*Vc}ZZ#uFNx#){C+!VLOY1q1-xRmBeGT!>j7r~}L`Kc0H1k?tuL%gNna24bLLmQIf zT-5Y|4lVX#G-7k=;;j{~xRMseuN_-S4%NR8$nDsfsF3;kZ+?OPKAwM16p%AeD;Cg% zMSqW0@47T_RSYs692(QFht^h$I+gkGXlA2pEwq*_jsp2Av!l$J0!p_)yWD!h`xmbM z7QErghM}P?*!M>1tZjxMb}o$@Zoa6JOWV&(9UnGIHoTv2+=b#%xnZ!8hbT(itVfry z77#j=Sr?#?VQLJwLpC_mt7G^e;{zeElj+#gkQHEsUC^;oXpmUsovfx`n|IvU@CSu} zLD(%%@brb}_v-{lfn}SnUR6)vY;XYk^x{xDoaM0Gx|*nd1m;$&Hj*#s)xQqNl!lW; zf4bio*$Q{#=uOE-wY^0K1mbbSJ7CSddFp8E<15j8RB`Io*xW(efBnV~UTpS&xlRb% z85?@A@0oH(G|pKa&E<|o|5C-X4PSJ+(0c-zKh#dTG57cy@MmjWe{{UJx*TyYa_2evQP^V11=1u` z=I`;CNo%JIlU>|}41XLk&FLj^$8X8`LaC1dz_V@eWUlc0i@>kx|* zch0q(!&3uQNL|#`G^JLZXz;}oET4j{;LB`8BnLrA_CtdQ(61Arq4)PmA=xzA^)+f> zol=Z;S|tcVk>NLXQBGQ+{U!OzX=EZBMf6>Owh22jyc^Rd4A#KG*OERF#K_5_D5xC5 z@h5t^EgsQ;Fqob~H6;wL)eIJ8jk-99B09PdWUQ)cn9V~*-Pxd??58RyVL<^ycx%s% zf`~!@Eg_E#B@@lNMfp@cM!(P8YW+~rpw>gn!3s9il8@fbq*P`VzQEFuPD2SEF6mLv zcG|Zi2^Kv#LW3Zri+atL0d6eV{B{iojwf91L?dVIRI8c+4M{oFq9-jG?#1J?O+C#Zq zf7=e)Oy{U9!Z6ex4_mHPBJcP!w+&+ zrNpP>$AfW$sQ?6!O9!*z7b26??4=_1W++^;jpC#ircMXU5*M7o@N^MU&s-+Ft;w-T zfT88ERZwoPD2V>x^z;u-uhn*X{CtPP&&yjT>)|b-xQ@p*^1E#^FCL=fFX(*sE z;%;alJEi zbmGRj1Y}7$FY%J>sACt)^dNEb$jCN*;@dKM+vB)@^$o$P3?FoaBmW=I)6mN)Sv7guHyl1TfrkcNd9INd4WvBSj_JN>znkH}m z*PQND+H2p)sNa~$p#C<0W*mp+7G2`^5_ZDFX!~b5>`(xjo~@D6sz~>XDc!CYI&<~2 zqwhvbWS3HgfnSA5Ow)_~CtD!7y#6};#A=rzQ%%iVNEP(+?E*7aqvj7mUtQlhSR@rI zgZX^(*{^%TQcXor|G=l*?^4Y=D1o{^n$Iof=+3e#k%oCv;b_xZ&|Zosfu{_u*ecaF zlO@mvVw9kVXO_@+Z4J%mel@}>(yqrS5zv^M$I@(OZS#MpX55>)kxP6r`b(@9Z0j&V z#0r5Slq(_?vg~d%S=&rH{f2H={5D^ONA)`$6{IfCiU# zK0<4>x5%4TZA`y81Gn+RoXV74bl(gSXuFVJTm~V0xyi2#g4TMB#JbiIT3+_6VexwF zvwdZFpi9vh`nC)xr3e12Y$dQlJtEu$(WlPNL>i$KkXrI)@+`ch{0IN~AD8It_ki_&6 z#H?D$%DdfNzthZId%~7YO5o<0U2&mM*LtgYZ>Jq0KVEAzLi$B!Lz*z!Z0mA?>nySR z^9m<`7Xq=y?~l;s1NR%!74%g~St_HHQJnPce&RPj--Eiix zgC|t9_V#9Q&NCF*%+^upl&FHw9?2qJ5j z!y{C|FLj@F`BmWn1qQI6yK0k8Lyqo5@~<6xi0bi{E?P{EI$Y%i!~~@rhXhebuDSmG{(OirT}Nb9Ad$lO0JP9!-iMW?!EEcKM<*L^`wi zts>}|xpi*h)Vk2gKd&jO1BEpYU}%ou-N7@Ld06m#j4Sv(=t^-E0sR&DEIBi*C?%ow z%pvGudTC8D`Wu>=YIiceOfV@50(y?ASwlCa)nqc75WFF6cy+^0y<~|ofX!8KaIsfN z-s#|UzdPpeKB|Oc@iM)^($bbq@J0I2H|il3?)_qI7gi_$*HLciv0|e;NprK3-J8cRGn>PxcSgU zEB;Td6r`M2RCNs<$R|gkej(+HmQQ3ox(b5lf@=ccjiel@*Q~-_a*g-V#>2gRGJ4&y zG1x10ukL3%$7RE*SHfQVeizK`4;TZRH!;@Rt&yTTlg2t(l`FrC#Mf-dk%+K2D}w(f z`NfA9jzl1LFJ3VvgzP+%=cP4iOvxoxTts+MCK!nujk;BcZS*y0yvSj2p=jr(57$%r zm@7|%&hNJ-RgKWrV#TbplC2i`@5w|_V!s;oQ?pc@1Q4<(FM4y2zpNTGTi$rs!fB<% z7Mle*wwl*VjMeV_nnpH)b9c+0N=?JnKu`nt}}2$8LrXdCTz}(D*=6V;S9BBnmKs) zk)CwEq`nDuhWjbi;C4!56H52s=Dn$OY;``4BymR(prIIBJz8VsV}?$fJBi4d-oHj+ z8NT}ilP?G6zOPRz86h0MJq)SOm#>NY6f(x;n~QBNVDk#ke&fHK{Q*mInO7WN0@*+c z&3Awz8KsO{qycS#qQ!hzpdxFsr=hW+dTNDslzLSvY>Ztz*~j5bjPMyc>g2j)=d&=S zT5I#J;cVQE+96v|dVpt?dR#J6&E_@9L8@8z|EPO_4lgF8hucr2Bb&-3oPlrvDiB2HpR!C@h4p0 zKI`>yeLW8fsG6cbx|S2aJPy%dqr6??X*8|+s1GKA<0S!D&8LgJ+4rP;#ICc5$eazB zOmgc7ehm~VXKHw4I6?EM2vJZl5k3Rbk3A-b65?=*daXZjI*!{t)&L7K$ryhV&s`Zn ze4dwhWk?!>V^`(-!o6CC#bdhXQU}$$y;lu*GNQ9J>@`gK24eSZlg#m(fAgOJ4G{xw zUOz?^EdcBb02++gY2#NrJ??{|g%gUxBy_I|7_Ih}&gB zM9B3pzUZ58%|*UlOKpbm^p;us$F0(HKRIWOmStnrm*>D_=`c03uJv}{PeufT&- z0{YK8{@*FoW-4X)p8}K1_n;<5OcMOpY?qR#tUi&1E8It-9TxTi3aL3iO@1)z&ex=8 z!0|beRqL}qJ13Jc%O>Ms^2B@YzON(`zl^eSUX$<(C+cVFc!SQ*;x)3I^(;0|SuAMt zEvWJweRqGneH=`LO^DAcz*C5MSByy>1J04|tqS%L?<5XiEaiUa?PF|zOMGDIADC-| z(A+}E!YbzNJ{NZrUznlkF%#ati|(pYY%Kql3SO};Nb+w@XG~PN3sz>Ih{=ITj}BUu z&P#@jtecuw7~&L>1h=Vj#~B)fgNCLXHx`5X=X}S^mX}-mqa9@K2$m=Bg;W5ku47!? zLuE^1O_kQ2uF=(;c~M(etObMl$|BeG%8O4B1)6Q6fP&jM;A#j)Lw?NY zIcYrHa}QdVe5_~0n!3^lN_9X?k^gWJQa@&Hqr;4BU1UCvq{nMelU9cf%9xU=TG zrJJRayJj)D1gnj?Wi#x5%6q7r!9bdAQ87E&!Wua*8P|9w3VJO0t3H+Rj3-Z% zKmGm1cj+6RlnnmboJ_pe53FlFpQ*Q>pX7#M628B9R@Ujr05=dY^zaanrZKZ%`WL?l z3bvUJPu-AMk_LhFs-!@7wKuD6H>=i?VZGyTsd0RsL%&wyz?EW^Ip@<4PB1m#anE?n zuBZ@VZbu?F<_^B<`)9!>GDMeQNOmvY)P48{Yi;!D`ea@sE2o)tep4HRmxZk~$MPRA zaIM@W$e7t0-oMBt-H5(X&Qq+#SB}9`T&aTysX;o*#lop=1qFxS@*B_EgPDZMZtf45 zw70p^Tf|+9b4L(U9-iWLMoCT)UEWu!A9>;#Um=E4hViRRN3KA!3pkjQf~ z@h66YooLSY<5Ul7?Ot=U)Ck{aZoTU%VgESW`Nl-=9;9Qq#+FA+BMp3D?iN8adv#-# zlkCv_XBJ>8fg`|a0~04MhJfe^LyxsZnB;5vL2o)=GnT>YO!JotZeL9(awdlS-JhX{ z*2F95&}Er8ITA|VsG=cWdpYgNRZ8%&)q;6I{4r@g({LXJXBUQG6(EL2l?0D@6Z4M9*fEHtb;!aKgfq&DaAD7RwXWby9{ zS9D@O{GlmB#{2)0s1Gh%Brs{wQ2OGJbe9lw0U54=`{>sy9swc$UAg*QOYxAL>N4d1 z?VZz}PkkC584eyZ?l;~S&Q0c2-=qIc5H(A38t?M1f*lD$+r2qlTpQtiJEh(KOlPWn zefZIAhw4?rGVt}J8v2iP3bq`g5~xGlR&4Z@zqPzR9}$@KWbf568nOhP{rff;^;dGAxxdxpivUSe8rkKT@Q{Q81FO3q#O8~E zcrZBhdlxCZq}jigfxdBLIx)WJ*Wu8!2i+=Kh&NJUVlCv2aK(`Vwem`QfFi?Z0D-{nV97bDfl43XoU2#po;X<-z{B4nL--Le|#2rAp@Mx`Fo&2q|;Z}0|7H7Vuyq-XbGOe%Ws zRj5I};HFG{?3~k%RUh8x~jp|MxYv<6Y zA(V`(-;g5_VQW=`?4$f9LKKffCigDeG9iKPxt8zkazAHZ(jUanOk-{3U6SS|U`iZQ zz=bT;#k8|AAj*UF%_h}Czx7@5{Ml|kDkWFgyBt^EG@(C^>L0kmyi;efhT+Ml0Y`2{ zXojJe(ybl@e%WZ$s6JR*Z=CeAeh*&W7rJ zSz9!im}Vy~uvOjJV-6klo9+-lolIb^zpYzU89?Df05C1DQh36Oyf`dUlS@yxPB;$T=Yj|^|7FH*S3p)?g-RGW z>=b*qcAXqWysZa_c}4LcAk4EQzy&!PTC_n(a-Zr25*h^b6= z{!xGd>lqHH=_Tj0+bxLdEEbBvF+xcs;S)QzNhRBr*kwtK)$jmzXrj(@QHRSTP6D1@ zeaye>SsAkb;kaI%`YZoJ6d{Y>U~f2fr+JdqEAjE*)T;;l>BG+LOR_|`@-kdSOqkM- z%VOM)?*`)xH^y#h@*KZUVP9S!w|x`M{gr!-8FGqq%c#DSa6Ld)m{m~D{hwjr<%!cH zGKeu87#Ain$ujyZ=jCBShSwy1Dfc4Z)@zMQvqr|-enL4|-PSn?;As78tDZX2CX=~rO;}!ATt?38tMEu>MeUek(>cb8IGQ-X`vGHff+z&yPKyBuUk9e>cC*LT zO~)6$b@J2rUro+~THm|x7w<>HJNBJ{xm*N3)|q;m$fkexO3Dv+Emh(A`QkWjU!L{PrN=D=HzFouLsYUtbUeclQnGAE1Cm>4Eih z>FCNr&R^=|s}vN1=K#+Gm6CRdryC?*->#3D-*$OqQ|L1s)PPu6R*+?QJF9STi?lQ& zuN&}An>*SPTlp%AElK18!yBq#{x+9F~2^iUPA!7ugc0G|UQ zyRZj>@|e;ZCAa_@rRFQ0ZgDTLt-Xc-CA-T0(Gj&dqkrFE$2~H<7GSY7uRaRGDoP1b zh^ZlBAW>+?L<%qh;#h7`0EY#TawAd>6EGt041zYQdbn^#wD|PWKzuG{NV42*b!l!L z0F%tBz?(yQTfsu6?yWM`Q+ZaBSgTJUGUriF*PM#o0_VuK&uPoPh>TH|4JYD~ z_OIp&O0_mx=}sI3+!9wh!aZSREp#>Qlaxy2930O@avbXe4GCTj*CtOcg|Bk=UyYTp zq)xX#urLS4m>Dl{RFJbtLtmNurMHKL9EvvjrAbD}9k1e6C~J_lxB0Tyz-hvzqcFJ- z3D(vXLM!8rF2)+NbXffzGk9XBGlo*EDoP$>Fj~$@O60QlR%>d0v7L_BM?zPX;E^(N zhB)ok{L-~L+^aEqIhtjKyuY6&-xGPba7r z$808m=6|<^iUt2STS!YSLcJjE@ovJ~Z#dFvVdlj~6TA}zy2S08R0Z_>mDAaAC69tF zIA%KzQ_y!(gD#~NOdx2k2%M#r?NUnGj#k}}!<7m8K3?Zy0!^Q@Zx9TQA~MkE-a+)zV@^w`1$rKtz$;k7$+8+}3YD%xjC=ZQB@nSns+1R0R+E^&n%U>sK3L<_Y zb~l-k5(+Esil)6NkTs>DZaLv9>z}7eT6^Je3Yd|BFn>kU4P`k738(mnHv=H)Qs`53c)bTLn;*8JoGiPsU+r^=q zEPf79$$!edb(Ml1phGAK6eAq>s+jXljAKsG$u5B?}K^Fg;!oK<>;xWzhZnB%)5aEXb3-$L`MQ za)P1v>5Q@#Hu+*Vqss28HU;Mjv{D|@<&^Z4f(iwzxfR6bkA`sEGaR*t9K3J#@;N}{ zyw>uS|E1`hzgTS>HeCm%5(9O9pEzo7K9KjEGpGZ;Jc%)VoJ!VFbR9#I=OOsxL>(g$MkB z-y_Ex#~rhS%%eCw8R(+bwpmE~LD8_+MB-Fjuh7yEnl)38+AD?jg0lrW7@1OedN&VVofLZ0A_*wSg&Ct zBqR(DR^BUo>pLNV z!1dwfE6}4ri?xH-xl#ix7C(IikG*$(5u2I`(mZ{5%Euk4rNTgwvxUJ}OT|W%%nz>G zH!zjVWMgK(UeH(Z`QE8`k2dDtjP$vEEoG4{^${7M{A@qGFoD|ft2(&5I~rw8}CrK*dVYMATA~;3LZpLW(ceAp?47uY7 z*RpM#;EQt6wvzm>>8FeuD$mZKkGY}}Mg4Q}OT66s_Zbj~<-k#}XDULDLp_qc6NkNE z`lgO(^ND4B`inR#GWL`yjQO65&m{;2+b8dGw=pD$8I*4JciS(1eep`w*NfB`o z1cyUHbyIZukut^0b{bnd@dw~E~f2uBp!>V?nR5O;4?wpv^%5->AF3X z&EL94erETRav`Kxk;qfzHpWv)UyY>~F)^IkNi?7c6I~i^!i2Eo6t@mV8Q2ett4zq3=v#-*x{8<5s+%63st9c=*ff+u-+)GDvWq z*=!Usyg!=VMQf%C+O>2Btw~%5T&TO+ZI8uE@ILDLJiS@WM&0~1Y)FC3x(As@Vkn}NZ}R6O{xP8N+)@CS#N>ZqZF77PfC<6t zj^)NBt0`@s0R`ac9R7U#uXnq5@hpoVk%&8%Z(+E9NF=|RhSY4*o*A58IEtgOhgZ0v zcEq3xQkXi0F??gmqMN7P!B=*ZUl~a$xSElAu8`YTV0(v#{bLHr0}N&uE=xfdoxGP; z!wWD<-#vb+_SXCTOn!ihETiQw)-7X4zyzSWV7MjeedBo}$Gei{iTiL>Ams#Cnf<1e z{`UR^q(omxZ3&=T!-8G-l+Syt$M^e8aZYy%RzW<{ zg!B!^MACoDZ0ew^XtcKa0@Jh7#bs6@YPH<4_*wv;)9doK2R8DD&T%xd&@}_p6L_a^ z?%vYryTo^e)R?3yd5Yv8ylatMPNpLfK)CM*pap)$X-i`CSc}C?r2YBx$Y%*YMy&rw;M$L-V#mX3>FKaM6#GNrDdR)<)HDH3>4qx z7sx=__w+Y!rSi89Ln{XTbJh4hD<_G}1-!(m2Aa2urv<6OV;9EP?!M3-C`PDoNPO9r zx5L}ohCa?bycxf`WD*U4n-SNzVP{>IW8#^Mj?qJk9^~aw9=e)<=#-`m;7mJhQt@kwGR$di?PN`$gzKGTgW>LRh(Sn(+OdUOYS&&Em&MZ<06r0?cjNntr^@^r?uL*|yl$dzGQ`>`5g_ zwv>5?Wr*l8@*9+Zouo` z%XBGSIR3*}LzUIA9xf_GRGt^wIt<1liAFa9)CuZunpV0QZa}ESa(GyD*_`6bI!*A1 zMb*Ah#kj>z#Q;!GmqsUEZ!+D%(?y+<%w00yuhFL}Nz61I-DRh->9`lp*OZfP#}`$+ z3EAyaj&el2f4XS!v!em9NN1>)9EswoYBlfF5;U}Xog@IbhyB_XOd^a`swlY|@8f_0 zM_X7R&mHKQ`kN~2LBXY!l`S2gn-Le2d8vc<`W^nERH;>utCNebzFq|rS_yMejzw7A z3JQvO9yVWojx-LF-aC^xVefHnyp6Y(?u#d`KEEN(7MxrpzIdtEv3xHwd_at%h2__n zf!hIZ&$Y|r#Jz^vQJR4u>YVaJ#|4ajZMfQpJVF|#q{eM5<1*@C2jhMXj;Zc=OmQPZ zx@+)HBTGR^%aB}*=~I}V6OUS7;iVdmoD?A;W6Z%ou7aLZ=r#XajzmMmTkh52W_sda zRytrg$&g7K=5(*oz}CjJIwiP-Dp-@zH}mNno{2RT5Q>tq{gX-!>#?who3alC#UF4} z>CP`msYnT&48>%mbQfJJ(Vo3+K!)FN;$4#MlnYBp^56FW)m%X4eZ#_tm3u2S4g*%jNTi2>vSZhPu{E3{r+UOSw3*MH7vm~e$ zjhRtZTHJ-9Uh|I$NHR8i0Ywy?OnKsYC`(P2ISW%Fczkj#|87&W_9S*7tY|V`(yK1_ z3XFg(Bc~I+9dIvjcqwqO+d**dQFMZOxFJ);J$@sPNV1AQ9Au zruQ3H=<9wFNxQHvNE&i@rvibzG_2V_N*2!k)5aoh>^dAy&kgtXKtlU+nW^vA3CPVCumCaW|u%4hO z#G;3-fR*;wI>^zesmiF|e~H!Poq%A}(g7yY9TXcvTT4@COk)^dIqWdv>kBAsE26)Q ziHm_u919*B4&$SCsvXoL5LC63m?u7e(rZ8g*Ys|Sku^Ym-OFqXzSfy+-JW>0*`a!p zvk3jHO8MmXa>FxI`sBC&aJk}p?~Y>(Vl>hlQI$$TARL=#Cy{grJ>%OWKt^r55yT7BnZ9T0;2gA*P`}_k=7ls@5!~BH) zbJk#l&i_cJ$~MScuWt3U!L&fE5ifQP8lEUrf(z!<^R^2C2DR+GApcXvT9D6VT&G79 z_Y(Z|VJu*B)tIzsib3q5GQeX&oQKx|#I@+)=_SnE6q*dSH$b>|mtwubs-0Rq!4->w9{OM|}kOdyjjL!$duujPhd9>#Le3m+OV=4_v+& zFXlXt+bd^WyqJFFXU}x=lLs!AO7)snIS3-p@yEAFQDG~c#{D@OUy)K8ThTU?WP_e` zanFqSx6cvg?-^oid^dK}JI;rDA=e~V{W_C`UkFo$g*^tJyPq;%v(Qtnfw}0`c>>3> z_Ib!yu6rvr^o$-e3RQHhlUNDp6Au;}oTNWo9UJ70oXRA#%|STi>fP7baj3>|8ned< zSK7#23SkLei?U%47%zT+jmb+#7p9Op@XWAGTMCg7V{_em_j~q9tIuf@(=fM!8%GnH{!L%arjj zF1r7R^xf##*oZ3*K+YfO)-`cN#D;q@mQ@sPiH*lRFmCV znMF%=?12bj96oCOO5quUnH%-ztH!b;&wO?XbeS!#zLPo!^DA;19>xCgQs{iwOMwRn z&Qmzc2fX1-qhSWqNh_E$ZvT>X(NaZ8lY;|%|FBO2FL+%8a{W@F>@%>0W_nD!g7FQilaJY*L7(j0njqdiWKDs z#)wd|>1Wvl;wNe8jx?7EhB8A(q@5e{G7WAi;4BtFW~rE!ZqSqvLO>Kxp}|L?HH8I|jjrxS`nyj? zmaT}@iA>Ih7!OEZsS>l#39w`*z61wH_EZS6AS~!yOM6q^(>o?};YlP}*ldajBL|rk z0Vc}V)Le!_=?cZL>LKK|A&Q;6E~-$QbK}JtYrRw*)8bSZKZQQOzbGU~_&|`0Sd3+VU!{MyAlt}J(1+2}y zr)JHm!8N+F_NOTzNx>{EOM6j|3WHT}Ven#?_^P=7l|}W0K1!ZTq~0%S_@MdaKeGTOKSRJG!z7UzBo?VN2dRjf zL2^ew`9v2^X!bDw(&xy5&3Qa0;7 ztP39LhsAABVU!0*rH?@8( zx6o)D?(Jk?hTM=manstPW5$P0awL8wJWNb8Mlj_+4x;SSka-^SdqFBR*$n=wOF{Pa zril(>1LRDh6uAXgh)%e=pC+VAxjz0GePq)`WQj54hvjU=viFv)sTt(<$y`UE3ufyr zonQ96LXAe&nr+dmARaH`%g5cOOE>cZ_h*wYHM)O%Vg#}-wqL-{8QHPNR_t8<_;R|j z*y#mUKPG8ji-$nTWsPw~QP!emi+%LU*Q|`d{6!fU-BGla#1v8t<7xCoe z2;!dF)*4HIf159e#MhK#qBMhf30^6(=1&$Ksu}3U9e@U@WqmS4&CKA&MoLA z%@X4kyI&|DcqH>-xz`&?mm?|6(c z-f@talNGSU8eE!|(pY`2$02*LFsb)WJAh{)65JBYOx{3Y5BJAZ#)IZqc~~#Kt>v%_ zpRcHJS1r`VO1Oee2cvs9LTu_Bp%i@f#*#VykiT0d8=2YTD}K4r`!A#JmpAC`TKN|0 zp=xo&sHoPh-b@NUr{lp?d7>l8S~FaUYGK{Q5`S-WktolV4>R6${)bxWrOs=|B3IEz zkkR_Zp!})S2&9)(w_su$>a|^(2zQC!75cZ8wbt-_`?FdW1?8jOv2@Ff+O1e3w!4|Y zn7(b#yZdKcLLzJo%%zDw-t@pG^4Mgod)gk)e2XLxOnWaainuS9I*P5qJdjRK2~DV*kqXPG~dC zQHun)K}5AZ+;SKUxudOFM2g4)it(Ovd>E1kW!&!Mz};`{h!(7UUi^6d_md+P0cic+ z1Rk&?rZv2CE%s`-qp+8w#vnV}P5OTh{3f(q?JW3b%fxjEFJh@e?K|^P0p*bF*G30m zp9^3$FE+L(y~@x63iibHZB$Xp3TiMUONzLH&9B8--oxuRE8JgK+En5~iYTIrNlZ!s z!T)Nl7#LFYpIze@_+5m_j-YK3*8hjLcZ{y&@zy_+?oQI_IO*87ZQHhOTOHfBZ9D1M zwr!u-bH2ZexpU`#*P8oc-k+*dwbnUR``P=mpGT`JJ1ZoT$pf$(fh+%sI=Z`aZMo9; zgqBU6U8qg$d@Tw*;IQYq`7+M#z&O6vlQYE8=F|JPwI@%W>M#zp+Y6 z_bcyk8~`F>nb@Af_(5X;EK%x?Q!(rXhf*U z*ZyVF=<#yHJ8t`K<@`*eq>cyg>!%99QSY~KoAYLI3d_aHC2J4qp2=*`lYZZVlnL&y z649@*Gf?$0XZy^x={?zD28Z{Si!qcwT(ZxyDD8dD`O`};oQ&4kX^XYh*HcI6(`UMN z7)!UZbWp_z`}b~lvgo@EJ(`SR-l15SCjej7x>HI4nQQHwC((uHOTMlphET}fr9q#b z17WL+sE&s(mTXhG$e##w((9k;_vwFMC-S*NtXXro6k@_buTrB(GQA1RRt}v}h&85D z*t=vU&y-<%*9QY}__$DcUVyJX>e z^A#Ixe7AQT|Muam{h1ZGY8w%Bll9>_ZS(Ht9XF5HyUy8ywM>sVl6#*krDBQgz%R3G z>Qaw$C=Aj$Z|5*`Z-y+i{aH;Gxm)69|;}2K1WyzE}s+6 zsJ`HnktI1$g{1YL=cw)jh?Ae@)^>~R2`Lz|&9f;t;Q}HC1Q|YPf=|%AF4bv-{DoftX5dPG+&y z;Naz13?4Sc9`-|*^~ElOh;g{>r^6=l`s7{Xd816r?_XWV)!f6M`*n~`%aW!2NTD4( zfd|Ptwpc0shdQjkgo!KCZnX)zixWSoAao3(Ho=iAJ5h_DF+^@kHe~;q_1`RktrsR{gXC5OaW zyK1SpHXRVKTAYyrFf!LhuZIO@`>GVV?9 zs{5GB!4BeS<70N;ykqKn8g91av(X-YRD5vzhh#CKn`h zM6Sa+6x zqc8^VJ@B-IU_)HyLggM3PTnqpk}#TVHce#)``$%wT$c5_*fCV~SJ-{cz2q!~=}28Zah*SnAxFvt z3B<*7x2@cSL4OV;4!6)%MRJClLpP_TRIYGwc%Fb zAFp%daQ115-l7t_Wied#Sg>=!G^S5No{Wy*L&a>MQ)5mhJ1DzzUy z;DbTHOUXJJz3*Hb%R>dm3>K;S{i!Ne=Uf+YwSa>H8}gc;YDvwW-aFhq?EL;ns4>5l z2&8>nl6S%@!~HUJHP5!8@emBPnw4q4%D1L8<8>Nn) z%x8k+ez2t5bOZvGROq)X6EZ@brs4KF(5^ zIKvd%(s#16l7XXmdD+8U zjkr$uVJJi!{7^0@5s=7Z+rEPXjR_x>rdWx-^(Xg_Lm=-B{q0~4+)2fpt()r@df-A% zPN4?yG7)0vN$)f~NwJ8gPDBE0X!Yfp%eLRqkFZ_;Y~}nyxJtQf#2)TGcwt?#li>5U zAf{!m5^!>2npHldcLHO=zW+t-#bgy?0_ZWr?fm}z#=(WS^wZ8jvSX=W!yZdrbfsG# z8LGHPJg1ocUhAMgw}!V^lkb*!dhBtV)q$oH0YWder#q*(~ z*``DCN8Fzus(JF`9i>X0*NTjYO7zg$E+}AAc?0)uAwkxNMd(alLHZ;snvNuw!yM6GM~-=8xd+E<(mft-1UM zIem`1-acqy^@tO`+n1T`CjC^^)(CgdoEJLCCmj5D2@>_T=wAf=({kL@9OwR(JuU50 znIJiT1Nv+1v3g?(s6RIRThbbkc#9~pNiXsS=zkrlboS^YUS^KTH5$>iYY@x+P*H^@ zT9CsLZu=<9^BmiLSO(r!n^N?DR|isHh`?e!JU=n*7tuerAWYt{&Jz2d_5XrkiA||v z2AZqxPaOUyIuGru$?7QJ=K-`G+~31Cu1~MdC50|&q_zrdNW2Nz6+ZQD+lgd~tn_Zz z_E#jo!U4LZq%Zp)U$b}<*rcew<&Exf?jZ|z2S6ROO8rt9HMd%~t}Hvy!;iWZ0;$ND z=1rD~^FdjVjpkk9XlJx$$i?=KHz^{0JbAWC<#k8w;qvFtrp~-S_B($~QL<>iiFT z7S4UeI>?x4ZQxE_KDMau&dZ~8sm>OvY6C(-1h4XyZ?NkS?{I*#fIX|`4Vh|8h$t;_ z*-BYg=GI^(DyIVJ0(Qh;zzheryZsW44AhECWMMJzwY+4o5S@=(e{JA|jg&q$p?y8P z4>EZmWFic)ez7a3QBIV)lN#JeIqHcEwRp2qs`a%d-Yh$oR zX_!XmLYAX-&k^9pS-)2JMR z*V~wkK~UCly&~v#1AbPmKOGmO)yUo509(#@`)f<6!tz&C4q+=RYUseF!yr~bir5!O zR<5}L;Abo!ZG;)dx1Z_iTpwKn`R3m|AWy$4GEorfhR5Hexd%9j1Smv<@`T32TJkHM8Zz)5(+tfjX$5@n9j}&T%Zy^U@pXoees>rU*8ugcWJ8ga42w zHF4FweW(pR4`3wjkE6uYsi366$WQYoBH$44nn=%8FI)n?O5;GQwvq(%)Ub{*7P8D=ldY25Vn+@OL zY&-jIW^nT};Y0#-uMj^SUm*LPT2n&z+ZgZZ+~uav^Y^y(11dQ01V?>>a}syrH8Or# z>V)?UInl$O%X-6LhvBwpEJ)e*X$c~Bb8JEj3{Y-_faLi2^nrE+W_kls<3k1)4Nz?` z@R~6qZXZs|*T@WFlQ+PYb$tf=WOLIRz|%=LdpP+u#%xHK97PUC}W!g4kFM z4qlBI7~)?H-Mp#dN5|@}8|E}3WUwg={th+kCfoJx;+c;cG;4qvPDVS0I@Ox*kpY9; zbS{hQN$I0o2R5awcEby)jmDltCDTmtk4N-nIQVqySQ!nL8_bvG6_&dM9^$JFPsVPa zS%a**Z7<&%?;8V52RLQv8 zQg~W0lG-)tc3#n8*fWynzKc z{t!DB!T_y0gcct{bXdBjYyO;e8?$uI2T#|6W>Botj1{z+0-KgW^;hYnX_2}zT?VxbGR5v_$7fC$Va+SK1eQ~0_Bv>Y`F|HA*1#&IK0@wdA5+A4vY zhg-XCzqa;yZvF0;9`zlQHQ^NGtuD<8FrQ~Gvw+itOex^gr!S-BNK^uRQNE)llCRDg zv4HBepk6&NCqO2EvthB-*1cQ~yPIEu-Y4OjOh{&x#r8zDfKThe*$qZiav+%~>WlXD zTJZcDO_>zVa*FwCZ)HTWcI}(e2u|mK3qFy&$=VlEVUpm zd|*$qu!9ATT%!ZWoVYkrXZa7k?z0wT;WnhrKk}GhSnR2x*w}g2*~Vtuo^-{B40kX2 ze0v12m0&D?g_hQE)sn3s1c??aTEDp$mY|ny`*PjA_4IbTYA7BrZvShL7->7TIaD#3 z1ff&SF(PI-eWiru8j`Yl~#|`7352bIzfN_K?@MT{3MLwkhv`%MFv2BJB+Lnji2amqwG{;q& z@7jFc1{7!fxYE-;PYjP=Dzy$5Y-AuYGTx^s#ows|*P6c1e)&XZIzcddz!i8FGGe?G zVv7%xb2To+p~NTjmCe9*a&#flMrrc(q|$h~GbMx7p>wUC15O>6V~%cFSz|5Bry>|h zZ{>D$XZ`#}+L`U=ALFv({7$b*+^Vd}OadFkArIU{;cr|$G822GQP)z34y(Kxyr@e& z8~b5uadk$=2xXYibTTTeUBdG>(ro^|0IIl zsn@H2cqj^VzW=;;9$u|r*fbePdHMWBQxyV`P=sr2z;r9Hhwtw0-C%Zsa!-el*7b-+ zkpbZl=-?I>)rHaY;bGAx+sr--%mLTSKh0G&+bz)NWJ>rFe%rxD`;*c@$^Q_7q6yxQBIt4id7_ZI%o}`iVwPV}G3&6Q zqP5mDa0jEcyOAShh8o=>i}#5m(;CvW_rWWvA)e@)L?2udyfMDI8sNUy1y-rW5OD0- zGx>N!>QG6WC(wwU2MU35{V6t#WP0EarE=Pwf zM+>ImjQDmeXW-G<-**j;SOzf))`KzYc9er>vy2l@6qrgwn9Ar4vRkyMaaVLcz#i#U z%EB+>UPyYZ_seB4j{3PVW1>7qWWGzEZR(|j%nq_dK4$j4(SiZ)`8{g0@JKuYPNmMN z4@5&5u5UD5dI%jRX9O+Z>vPCDJyIDRFfUQeJ)d6QjbS=v_N;0>$vCe9n2#+#o`z?x zfk2<5#Rw?YuYO|+(9lA=sfqDQf3fT_ULlMMy;-t9GSc^4jwFvc)G}Xo4*Var+RMSC z5G)Qk8CJLhO%|cO{Qz>;-ux7Pay#@FbMkZumspm=)ks;w0UOuP8pSNUuCd0>mwP3z zGfW>0?EW}NZui`IIUh&Q%o>#L$*$$N<4UrzEJ38UXaBeVQKT&Mm8;Ky205tYgS1!>J;N zf7fD+$YTG@Qh;Zpi2X+f{w|uZ8O2oCRCAHJ(waAl6$G1m36JZTPxAdU_63K>V}6VETghCRKdFy%$jy1r z8XLnrr-I9vGgOzyX;4&lSJ zk8Ub7Ycd{F@+$B3VHcdtHy!B>Z!cGa|Dh+SiYaYr*yYcv=I&x93VfMa2|}uAQF7J8 zyjh?Fiu1Hz9nMB7fzld*!BDrzF9h`KQr)x+ihHr!DogYiOS}xQiS6t_T&iNarItRh?Z#4*PgW|4`32np z)3GrsO4MuPDyIPD=7KYvB1%y^xX&NV#FR`o7^UB`PHrEEc1CY>_QQxD-1*gI@YO96IDx%x666eH zaIp35V#kyx_GM$NhT#-K{YSfC?hUZ<_Qg)E{cTNF4gnZMXhr(c-5r zU4wjqf$>!`kAjLHi)VO(+nAKH&6O0NQzUh6L6ZB~xMS_mqPwn@9Yzi*?Fzly(o*0B zZ0;eF0U^2xL6Bg_#`emuW-$_Mce_KN}`6`phI|n2?3J4q?|H3hJI&zaA+n_X9#wuCfRZftl zhit&~7exyrO)4qts5xo~Va0QN(L*j0zB+Il`-BS)WYhRcozYGfybp{X5N#o2NXE1z zkI-A*;)W&Q2D`?A@9OLs0g)Ox7@)&Rh}vZsV3wN%DEQnwdsc)7+Kp3{nDJ6^W6{xJ z5vTYfjhc6Us<1eimq!n1e3YoB_{7Cy734UCd1T%CSYQ}KSP1_6xvA+!&>+mnhi zdrH_aVGM4o@uYDuX)ETdi#99korRd`f7ig7n6neBV-Z)A78EMZrz7rOlb8hXQ*9w1 zX7d;xbgAOTfgf@YSUDv9wXi-MbPpl=!blmf+N;0p(yM|Fqmu-JJ&AV}qDxZlGX`<6 zy2dGT{@T&f)}*`6IC1iKM`KWnlfsuC#44*_z1(|O+wvwj9d7Cz3O@0q1pS3~kPkUz8c-MU^VMWt%*{*McO2(;Hb>S<^|BHr?`Pcw<(gM4&F z0_LZq6X#FM#(Thc?#+FN?7&K!QIf(-?^XBm4;Wa_M}iSLwr}a|D6m6St~IP=aw4zH z>0Oll)jw>>EHs)%=Wgd{4ZLx-9JAKcv&=YAeSPFPY0P>>y=<#kh_9U zzTqUVl3oxv$TUYsBLGuy6r1wuk8Wb-Dl&DL1clLW#>MT$s;%6rs$0!MO&;SyPk!Fg zTl$;CX%MoEu_GX?+vV!9Pot^4#pGM$`WIVJvqm{Li~@3UtyGX)Xop{jf9%p3}y&%RBKi&d+=@6g7q)!em?bg+Lk zwKw-Hz3L(&G=Q%znH?WaL(kyygsh?#(si?A{h_EsNgQie=tZdgo>|n}x~aewjjY)z z<%uU&4x@pe_V_!^!}petK-cH|n0BbV-`KK_*4TTKKT~SbXimPvX!49~s<@Z|e^+3A zeV;eBLy87)(^4W-32d^M75so!)1X3|NYH(I4J&)K1RM(|$ybN`B1$|TiMuI$s}zb) zSfbA_MwmgOHzOx66R*USMZqGpV5h<4r5o*)OP-<=w< z9Q(Iz*?o#h5VI5d$!ez2()>M__hCyD->c>YdRAdmZka`juL ziG~nTS~J3^wc;9sq+UMBV5t_o-8pJl?R(o@ziFr68!p*%%YWzH-(=y5(h*UKkxc{5p8`_=H(- z+f{wM*q;8}ymRLO0Br0oAkuiwpkR?t$evEH_GGgU4ti@&F)9mo{yJ^FQ{<`nS497s ze(#$_D#LosC)DA9P#;IFJ-a^~)CsFQMO(UFpZ@&de96zaRz4n{foBu)b~nll6K{qcL< zkR9U39!(ihkp_EOX1FviU+q^Aq|>M0^Lb?Yfi;JCf}T?W1Q^Mc@RQahh`gsYP>YU~Cnksk*DAGc_id zEML}cY3D!Oas6RMKcu3KSZpN*q5~#`KgetsW+Hc?wS2%4IKytkg2D`nF}S`~$*x@L z;*#UTs>d3vWHVze~eNPSHBoLBXEp;aBg)v!!D2af@}V%1Wk$s`SsARS$H zA=PP8sZ4)&|N2Eu+VW0GI>P1Fywe%#oJj?}8+S6hfqVWzWCVaXkxY=l{J@H~T+u&$ zI03D6KhV9i7w)%WLB8U^5+3yvev5m5r-W{)#XXoOg@yg!zfCLckJbj6Ow-r|pY1lNW8|0=iaMdp+|_=z|G&X&ySfqC5Yd9#{4eax zjXTn?V~`)iVboS)BgfTeM|~V1XauKpg_O+UuFYr^3d_R%yJY1}#gzE<3wg_^$r(8* zzCnW}dB{!sFZB|{s9)M+1j|xKea=!B%Z)x}s1!;Xvnh;eB>^6PFYhy@TufO4im3cewlCwT^Uj zE{N|z@qe7`3iY}y*>DJ^c-An~HGx!sfZe{g>QSmNWmYWY=F_Kk0-@?<61#t>YA+KE zxF9WnwkH8Z%x}DOOzF3tv4kw`QCFRj+%U|k9OpBx&YKy2K-j$@~If#*aCIa1fqnvts~<>X!pr*txL;iUIPi?TS6Y{&V{^hbHri@uB z!z_c4sdE`5xj@D#v5$pq0e4kQpr?wFK3?4dHT!8^N4ZkAXrlBTl}_ofT12O_#{|sx zs3kuSePnwme7oVMtpift;ypb-akEGqNmZu#K3)gvPKZc1nH!migUR0af^;-N5((G3 z-qXsP-ZIn#kWlX062CNA9v%bRyCJ~Cz1u2B5^Ca<@Ylg_&xA~>)v?DmAFDN(NT}{A zmi0UxDq%+o2N4Z}42Ps@0C>hMpr8>8b=A)=H7UiDrJY0x30;AePHOHJcBc1~n0avs zkEgyIHqyXk1x}rI(8;4T8!c@u@X zbP!E?D~%yfW|%mjeu3E9(_0w0??8$71Q#l-`^g^o|F$S9-t-Z@qH^XBEk;JR9^2-ng?sGCF$!shS?iqYhu z;A^o==>Z?7cqT@CG()2e9?d$VIVi}IBH+(!;Bfto1YKp5%ElRdq|sQ@X!&vb@Qrm% zqI6ca-7A3r_RT(Rky(kWf`^n+Mpt2FF`nAG<8YFL%8OL3HF zOFBD&)>jk%Zu^o7d17nMPir)a*hMKTPn`Hc`lZ5(v6e3^+E?%WE>(JU; z@Ql4fVv>|6PM8v9>|nSeB0};zdINXQfd|>L5V0l&Yp$TIY}2s`{oRYp!p->cO#30# z8zCrUwLn3#tNdu&N@03jZn*wQ{Xe)gaq%!G)w>NI@!^T~kX%BZ2rc(%Jy_Uuhmdrq(JS06+b*9?gFAgEW52MeuhbY7<<&*><- znzmqQxViXw`{#*M-hJ95bq%jp4E!Zph6)YgBOlIZ+(TQ9dQ;y3-7!k%!{!^;QZ1Iv zBUL;D^EWN$Ohjz{mj-xR=g(gAf&J9Qq(t zmZvLJW z?t(6eWo;r}gckO)Z=PX|W`Cl8$;up8plT=%PV?DVP?&0e*w-H=+o|*SmuwoTd@!Y7 z!Svft@e2D%vPF4B9+fC3xc@!QX*01dy<^yx!u;En)VZs~a0;f=iaGsZ*aoGlOVe`0 zEi6Uf`FW=WE^2i+N#iO{TFm_QG|9dur8cr~1#0&D5F=D;o4CL~;36WVRstchOmU?FZ;?*T?afpPuoW9nj@UF^9OU0!gB0A^eN371y>Mdi{~B@y#LcXcaiJzXOt@#`pw z|3B$=B)osUraQ2gi8Xk3oL5dWXO#|$4@WBlWmWAklOM9IhE09AOOSFFhF&kJ;Axa(N5^v-8W zcGj-!u`H7R0;qpi_hg_Pawz~VcTmab2r<3l+SW+%d>JkNcR>Bl@gG3_Lo}z!{yX}A zX%}*Th3;kykF{U>9;9mb*Sxh{d=*1&Vf=}*u31F@qEBB8|L;cO+6r?wW7gKxaa|bH zOJ#9ZRSwT^Y&2ZKdTnq@IXYbv+VFKo$R5zo?5N)T-4J@!juvjA{mz9w+@XWAOSG>$ zh4!_nnBR$Pi-rW6gw@~D^`Pi!_*SXH;zw($Js>()yauvznrh8)#pQ04@SzlKCwkSa zZt{8QTPeYX&W^ z=bY4nrzNcmpUkD+k>h14!a?}zp14}q6m*VnXs4ycp4U>BGjCI$w>>jDecLP2Y9r~s z;e7Z}!JmstMmD?H&r8DR6DFoC&M!^7T|eWOp2tDil00)14QXj|FTA9EqH`V`z6dkl z%*m-|C9A#y!xV?k6LXX31?0~47VfBg|63;peTN6a`VXPU722A-e61b4({)tzdu<%- zk|`6rB+2YNi}kT(U90|%V^6Q==dOja^-P}x5-zrbkV-DgHPm4_r4Oi(nlv+YK#aDZ+S9bSCnW9JPpht>=hci+ z4N6}CaE;FrwxM}Tdek-|T-S~XWl=@y{bE287n>GzvIz|K$X|V=Kh1k{voU7jh;dM& zNRi#k;bo{^cVR&J7%i#dZuKY$#@SCJLUhdf8F`b3NA35#ZF(z_!X@xDSrmdR+y#q4 za!p6@PLKeD}XH?%HF`z-L<32?s1?wo^`$ zn8O^0$O6+h4+3y%Vq)enXF>~u0hzHeL=6c*QcNrHy(Z#Ucf$MYfU+{Z()Ajt^JZyT{2oGcG8fB_uPuDom z_rdJYgZ^6X+Z!xNt&b5mbn_1rS#2*Eb` zqC3MaEP+YUGO}XVUGU%XLJ$MUx+IZ`D0A`Lz?2fFDS!R?X22i*8|*j2Z~jD`-;nSe zKMGRt&2cDIQa_&f6%xXfC%53qzr<&i*INV%ND=8JPG&st6X>lwsZ_ zXy4%cx1Tn4?6TOQ5-l)&ylA{g+g)1eiZxKC8bj!oKL7F9zZw>s^G7ae3~z8CJp5Kb z928uFHx#OXwH+tNVyy^pTVE=bw~4c7@*Tkk0Y}h2H-bsX%E73sa zYE?4$SF+=s`;u}%z8V6@k?h3JUq~|cd6hmW%xR(aS!H`h0Szgfw za~d$D+Wj;iPV5>)+u*XJa2G*1txRtUZ6wv*=Y5ERqcQ@T_Eb42^PoqnUL{i}Q>w}j z>ix|HDG!&R_vG~s`=VhFYX;m!eqB2%QEmJkww>BX`x{lA^`9na2C@~jElB7bVYJ;E zf7iMsQ)gU>C7-GcuNRJ1wy5|Fy?HiTvv$al(r!0@JyxdoS)TjoujhNe&ol{;BmK6! zx#Q{Vx*|yb+wIkHBW;o1YJ=UxL+##V%N9+Hh+cI(-wQa7 z#U20Rd?1#bjm*07dzox(F{te9AxD{7mEyp;*9l`OE1eh^gMxRa5<3Yy*H!RvI&z$` zem6UKM|6yChe&y<^C3;cS{dUUHXRmWsrKxNA4S3&lVcSXTR6PLO_oQq=X8NiWp-o! z#&Hd87RkdL^J1$jO;lZAKtllzZDgZ47EA;Mj6RlM1Si9zR+jznLsDnCA(Zi23g)=B zCbe0#fR(nInrH23qnW~MBMaOz^xX@RH+^ZgB&(_J{#%aRL4LNj=gX7bVo60CwJx2V z2mZzC%c0Fxo%P`KW4S7*%E7<#-U(XvD+F%sMNi0%o!-x?gm1&vV^U=_G=@|VO#8+W z8h0t?EOTce5l+pcx$?5KcWV|0Mh?q0aQ|gyV9kHEGPgn}MMESgD#+Yuy=i~)DZ5V@ zB02NN6!I&g9@L=mq)z-*C^#i5?>FqJx`QIwRjc_hu&(blmU|PcoypcmbVE({DNP9R z_h=muPmm%O3pIZHb#^8ys%K0V(j7R8E2?XlNkS|Uo*sLr$3easX#>A0SC}!RzS=p+ zHpWIgve`U;$a6R1W0Q)=6aC8%IZ=gCUEnrPyz$;~h`N@dsb7^(`f*O~lZ+#XS4wbVKn{wVzhYQdPeX66tDC=nVWTG;GJv<)OchWGF#_E&GA9G%B z!3fcEjnA74x~o&qE)b7n`n2dA!H|@*C)1n;(v4zneh7%E9N7;M^Ku(cl^`><1 z2L6&aI#xKc7E-H|Q}=p||HG31z|V3L9_tq^yyF2{SYJkMb%7d_D?F&NkTpH0Tv;%u zg#?yp43XT4LdIkNQQb*T-q-pMLw3Q7Q-U9OfO$4-B*BTroaY6vz%m*_--v^CeeAM* z%aD;av1SWdzAOwki}7lEIv(a=-ENdxks?zX!`Co z@h2b~Yj90){UyI?{h2B2M^00AA{9k(B7 zjL9EA40K68bOst9^NbOS$MC+KWIL5qUkc9kq*TVm{_}NZ8~+{ztI#$oB=FB!3mrU( zbj6g@^9uunuGs#L_E~h!yuI#rUqi)7Up!U`Ve^IvMyQ(Wio??30Z+jFIc5_#60?_J zvbEyLVsbIn`3A4xUYhx4PKVv`VEVkwIYQ-0RYggaA|Amz5Z91$&Gq9Bmgf{eMGK2F zS5O$SX1q{TE;0-C?` z92bHuH1sf3YO^VOYuD1B(JR>zKc8+zsv}7HgsCHE>5Pt;3f?v|8#tAU9oH0m(SI|= z=j64Kz63$Fg7$!BvH8Jz);}<^;5%SWVj=XCLztg_!T5ca(i-WdZXE5w%lrL8I@PMH zboL6Sn>X>!bq}8*?DY&eUCCi+OfO3G#O|}z>D)Zb!-d?|)l3ZL%kunGWN}IG#cEH} zsd7IcYc{aUmOC5w4I*qgT{1idpxol|qitP(0khTxmZ|myd4z7<{-}E+-Xp2Y zzFd#bwsEjQ0}5O!a!0GIAY5EQ9K6$lwHRoM&1Ah6NJ_DmH`^{>U_VdUV+kPYE#^)8 z6kxP?VK=m<)4Nni(#NDpVDBL$sW?`DSG_I?N}cYbcZV~X*Ns9GCaT01dZ~| z&jqFRs*7S`ugxOjp0nuzCTk2=lgf|{q+R;h0n#+ChY0Y@mmrt~`Jv4x zb*b&cW%OsD!9T~{95V@n9W1*()jLhvnp^J?}@`_QsZos_acd2Ag~{w?kzQcQ}6LX9j5lM($=mUm&P~g zmlCl85w;D9$V$G4dQ*RtmlYaBqVk@_7B-aTm*7(OK>g63t0QWX)W`T~L#B1}nn3CFRsl_VpdS0=)pr`(xg6^ICTv4xO^R2bR6LG+i|>WT6hewz zs9dEvVAjLsYIS<_z>&&r>F7$t#B8wf=EIvl2sI2K*_;+sKZaxcud@)Othnk)*`8`UGd2ltZZmhVM&ERe$y})65&NfO zPtbg**xvEOr`%ZWOn?ocU#Jh{esmkgb6PmO~H59)ziGh}BIos;a#i6X;!xj~rDQMhq z(MCpQ(*n_>NLH`E#8A5G%`zp~D@d@=0YP98y=c_&DMKi9(eq3urW$Uq9uP-PcJsp?+ahfrBv~VJ_|c44m0pcLlZF zD)Zh96QyrMe12B4mz?X7VQ(jf5|dn1^xY9k#%7!BmCYU!!?&+caV)L$=gET5vB7{h zzt}_&+?D3FDlYwr7b7US46hB1F>Imq!~(BH`^jAGg9wf9gI?)395?#<92 z{`V4ZJdJa?Gu8RLQdIT3hi?W@Hm;b-q6j61(|Y^?rt8b@rhK#>F4m#4Wu$t@j`H+) zBOA?$FybgPU~&a#+E+gDg%y<>8+9!M4qT7mq@dc$XA3iNZZ||fg5VJWPqIlMrqEBU zT0kX~zb;GktA(LHn{*0?UkT1yY&cB*Hzb%L-wX_m1@TG0TeTwyNBGLqE|Qza8xoHN zYEibwFG4hhQEXjW-0XL<@NZHJ827m8X@9FfIH7&}P=3MDw*}GK@O(01HM9(PF|{t1 zMZ};?K#nLjQ-u=2WkX-t?GFxlRwiGV0wukx?a63HShFD|kFJc>+8`L0Rzu~3x z(|%~QA6wKClj}T&s2+YsWj`s7`*smhL8VK=*%j{no34@kP*>+Zt3rVf40L!9V?(<_ ziM-|7Luz059830yiM^~W*GK1#En`Be0a%Afz^U$2oqJr_eJnkbTQcmG{e+JS%bGeWwT?9EjODuL3U(o)F&`LlkHk$E0(`*VCX=7A zLH}26Zy6O=pk?a@2=49@+})vYcMI+WcXx{5PH=a(;BJB7?(Xg$TyEub-@e^_&v|3K zd*7>HRipOaWAFM?YtFgW`mn=zoT9|GC^eb{8mbTZkf20WEK=w8oG{~6qO9%cAD=5vt7SG)$F2$=;6f%2nkgd5QW zSBi`OS=5gnm>lcZS`T8&mP~0q;9ovi$W}Dz;kM34K#iYn<$<_)Hhj@x`$;E?83jn@YL*B|8*r!$M@e$>zVN~NL+FPz)+bD&(x&B$P1ws zV*(a1jLe*AvwaD4SA~PxY2iWX9f6H}=)=+*<14m@wTT=(orw?d06kq8g!7RxlN*ZJ z#l%xSl}VQRB({sBUJujhR_K>b8D!``;0BG%AUNHzpf+)c4WsWX4(NG1M|{MaD7Q?D zCngMybU$@MsUP&jh}rfS$1$LOsC8XR8P=8#RnfeO?~c?ba49jULaI$L;E8+?cRV@l zQ{x?j^@q9Jz6HjpfQW%|%X;_+)CWTOKg1T0Uj83Ln{nPx5H>G=#v;_(g(gMz%I`?D9&Df9X zfOh3=ob@az;`7^Au3^fu508iu&aU1F~N!kzw9w1d7$YG2TSL24Tj;}s2J^(l9 z57lwi&uRC^A&&fb+vO$Dt*j(<{zF_~Gd;Gak+o5za#(>|vTL|#tWr$(H7##l&`>KG zYcQg*^xPq>zT|eQ-2zN_;L?7k z>*+&EC(22G@zp{pBZ3RxSY4NX-Hp!wQ)ym2COyCBp>PN{HE*<3cYe0v z9?&<}*s)XQPm$b8JWerTlfO;n&4ce95VRD0=b$mPED#C_EjuS>;p1sJjhbIjz|&<( zZq%HKWLe7X!eE{-S$8o1slmVNLi4`3(829b#b*o1{#yKHj}h>rQo(nWwBg#b=(S%9 zgqyR28j5}p&tXapdqAK#@$9k#N`r2M`cJ`CBXyn3(}JzEfu$z+=0OJ#dsn- z?N>avV)+CKcI(aW%nv%;(P89%?>d~#;jEgS6czzBukhgZt0;P0BRe8+XM^6^Ak z%{fv>CsVbepS*4!O{8GJwgEV;SIo<%O>q94EreNCngyv3tdwIpD_NUn_dgrxu-9JS z&IGSOcAgTLUbc*o;jtY}>%D-de&3JPSlVU)zh`_*Ge_EdSAXS+=)5%48&f_=4oTfyMW zPU)|jA!H^t|A_OcOMd7d9r*`@Z(sa_BZWqRSF!GF1H>*~ICr&QoY@#xr3M;IUVrl? z_(F&3OB;Huu@i;Tg*pf}Pb=B{4a~C4>jXJ-s1Blp=W%!zhlc#GpPlsePBT;3Ng1Yd z@V)P+>h#$0QJ9L)_pfwrs%m*yuA(j^aMGP;qRs9DtbVT^1F=LC{@<%-JJXR|?zvYi zgyi>^rZLonFfv9R4-K%Aq8>e1)utc?2d|9Yj+X1uUG-!(b^FE5)PBV`q!+E;qDI90 zNdM9tS5%f78387I&{Sk2Rp-y>kN4GfYSBsvU=68U6ATG&Of5uVyX&J)p(%td_2%`n zh!W3qW@*QwTD+$>jcjlT%in6i1}rX1E=G}RBcnZS>9OeUb~e9QvW}EhPhkH`(#Xg- zp|>pkpozT$+SJz~1w=wn)31mU%$F~~4>eea0SDmkB=Td%wl}eS2RgD-&z&<=u|HEG zE}1yuasQx_s}AUi|8qw>R$V9S`=$GDjgt6=6W5a#o}G*BD0xWp^3J9m8RGIT0fr3T zd{j@d4t+#>Ah9mL*R`y|lluF>Kh+1P`XJ}s%bLH#_quW}vLBn?VvU!j(EL}Gy>8t2 zPIk7(v*-4v86`_UoLe;1Z1+#3{!TtJgX-Xz#w0DB#O-CjG+J^tCV4V*8s! z5#5=^5-WkVIEC#s{O6~~-F@BgMJ`MSGks)mJ>9DcmB{Du(3?|F%mzC(ga$f;8B)MK z0%CSipf^Fi0r5a(5~|GxK~J&?E^ran^8Z389GLwJ-}`84YuT1aMyQ1zK+FXIoE9c4L$CYJ&`w{ua=>PgMF zTaz;h~Oh z7EJ^{b*xt*GURy1xp%Ki`6SyMf{OGs5D%pDd~qO|7~pjm7;%gmH>#+o>uD66CiBr8 zy^Ef+*OU`O{~Rdncm7B@pWRgvpSs!O!33UEh!1kMT}t)@$dj7&Ixw(y%w0=v=S+$g z>2dy-KG0X~um`t&X4n$31R&#Kd-=4d#o}#TrjV@l-Y>0O3k?3FhIe1olOxY%27FIo zVM)}sGcBJe@}9$_Wh_A)Zk zVB@f8Wy;%Apws^GL1&c+kN}bkqj7&l!ps}#rVQQRcPg#xHR8sj$qWx{e>o#0o*lCB zYWiGqg=m(O2sEA)e#kfPzUGa^(NG zaayjl|4l)RD3IS2JQk*L-DgMRwzFLd1i3g{2}8k3B0JIQAl*4@gd=cvpoe6Lej+p@ zV0g35ETX04IwpUKrCJ|g|9h{y`C}ly$41XeR`?$IrP+DYZQ?!F$qVHrwpUvV3eHMW z+MogvN!^uR5a`@bm(uPJ2^GUo@) zE#`8%e@YrJUtq8!*d3lG?)h8TNeIXcy0LOqJUU^qxmW9pa5+IZim7n2PSB#q3VM|x zLdMg`&g%GXl?Gy7+fAc9e{7A1(n(HBftc4F)|;0-mmu}El(gPx6k|LQ1}m3!g~aBr z--=HYVK5PZV%(&LkYI#lJ^IxK>346fwQM#fa0 z?rl|lA6ghHIx^0SuNLtDzZb*J{E#@A7s%p0H& zrzw3wmtX*{(j=p)$6&}@sj zWb&)R%_N=ER%W(X-UGBr2d@gB1COiorkzp|&E`4bn2Eh0Ifrcl3SxorD{j*^YuYWJ zah+FoKk$#AcGwd=LBfL}=i7XkvRLm5i;KM`E*CyX=ipuSVy{Xi@CE&~?SWH_e=zEw zyN3>SZdqE?i`Bz8mSGQvxLOm_lENYd*&1G;=|^XFG;6UM2^pR5U5LD}8Ayg6-{jNX zv&AcygLIU{ZDx0tSRdq9`YXi5JEW7W*;Ej?pP+WEAn};oD@WVB8OhB4yei&VucR0x z_ksB{{2W{w^?KJ;1zI_*Ar}SRaC2UD_O3xDPl1(Adh@rm>HJ89W zZF)yccTE?!LB%=CWY&u?Iem5aG<(2ZI7?Tc8x%oe$QoyggQVuQCLp9!N>vU^igd-L zGpF=h)ovo96*F=AwJtBKFk|HRVg(boil*7U%Z9hSF>)ijY-9QI^!A`f&u2qCVSY2AHo_zC(S?Oz9FcMGv>5&B_n#l`^p_X0U%2oy zv?ZkItwn_I2euoIn-D&lscvpDfQ+^oy*dSL%v0ygqt9N$Z=js^UmN-VAE^b?B2ljB zWx2Tq7J69>?xvjaS~ixxOrDVjEY7gG`LXAHn{Yl0M9k2iyJx`|J6)$y1rii&#*i6I z>%DE!Pcbc|h+Uo7sK9GdY!hH^drC-tf-`P&?w(#-a;_07c}cM|%?pXisBUX~ZPor* zuv&b+KyfYM9&y(2U?jS-z4cQObAz$hoo9S})3u#EVK2ex$yZ5gt)hH;_G~?>{O}lo zF?WEj(uE=DS9JS-sRg`2LCC+-0?kt;KN0ODOYjz`4?3e@Z%f<`o6|b!&PT-Qfr9PG zX{e+*S!7m*Al`%>Kr=HxU>~7mVof;haNJluVF}+A3Z53%TEEBOAB+aHxJVSNiM||~ zqF-u()*cW6jU*AXQqmfun$3dCuB9+}jz#OTdRNnd8`X5aI()gP!30ZIjrk z&2NbRRV~Ol@}ztSR$9$6H-N*@mJM5SDGL1K@kI}I&jjNY7jC*dw9=SCb2^nBN8Jak z{nCfh$?N!_;mU_M!l>xP4w24afN!tNB1I zZVhl^8_Z^MY4==$^?1m_qLVT~2hvfb%!4f|MU%oGEnh2m)YPX<9HEBAzuXbMptmcC zvy~K($y`IKS1rja2W!tEPJgE+|5Jy&zJWXXc)g1&=*0~I)ur%Y#XGgUYf%8kkz^vN zssyHNQ+x(3Y>!sopE0F`+yGNIt7diYo#VJW$maJ7-N9mr@?lBrVXaucX0u*-GM(E* zB;Gk>zsYpifjednG<^?|Q|lKxzfy{7u8XP@p=K=rPcEFNU(b$JatWG45O$wTuKrIw zEuXN)%#!$46bmI|k}~-2lQm-oH?~IS|Idnc%;v`_a_wiHT`bL{mF+5A%(&q4BN&() z$%?9pUk~lu6{^zOe|TNj2pmDoyW#-0d3_znBIK_IImz;b(_#Fi`qd%L-N=kYosUIh z(D)CDJ->zg~wmo*Y z;NkJIqg93-$)q{e;%Y24`HB6(<_YgLowFoDzXwe)tEsE&(X$1G^PZ&Ny(UL0mPjbzUIK@x&fZO7s6%a=CtDRiZwm_f}Ppufh+yH6%uNAoq=dP zk!iE<8;a+aHrwaWUidx&9*O)b%F0t}tZ_myAzaWRNWxOJ--H|`IvK5>J`n??#e~%; zVhSYDs9nnBUyN=w?>3cOEUwNtW2-6#W=kBIe};h1%rX_YR}UlzH|@a-Ip)1Ih(}$Z zMU;F6vy@)O>9A3%xAP;Vr8Bd=vZh~cN_}YOAeoXDz37*VsPrwxJcyDtjv_#YDm~M<_q8Q zdRTyA5UeVY8H1L?w=(B6w>RePvoYOVG~hqR7 z$c%53)XUp(g1ZKl+|NO!lo@*+lFi3=>I?G!pk~hm{)-y>19B6(xxudL=GYh58~4}j zJ{_v#`deE6|JDmb_X0p84Q(OR3FCExS~aVluB{_*JigcBZa$|{w~M5#kO6LZ3mh#- zVEl~+3PW|58PE>aeK!7R>3f`mxZPU!{_FciSl@m)+>w;j5f?Wr!9~pktpV8bceyw@s5b0g$8JM zfcx;sIqeF2V#I{soCQm^o;bya%GmTD>#&KjoxSu;9<>v`9*SdB*C+EfZA;L0{7Yg` z*F~nr^Pufq!@Z z;yL(OtV4o{=QA-pqYq$`p0RDMFtJU{fsEWYvI=h*QHc^y#7g;&Rd8@y_FH1EIMC9% z<1!A!FeGE#caTOO^3O?TZaA4&;Esj>D?)53$=+_qUcFVYv8H598<9AeFmF+ zRaDa*X$|UH{@f&I7s~MoPMs*JI>iMwgpMAg=YHia3EuPrImRZGFIGkD{gF zC;DT8*L~T6n78|(qNJb~`E-BxH^!%5^!nMSnXJRcy zN2R)sO92z%D7wi*-MYs=95wUBT3h(Q{&K1?ok?KM;`c)>1}LJe@&pr zpO3y0qN+rMvgx#%HXYcWkreGrvQ-cHCt*ylfgaU?Gw{l?n^MiO!oNoetoa94)M_%a zknpRF!~+b~)HGZ{H1xa<^19XGa`UG&tJ`Yde>rDByv$s=B)5`97j=8=l?&0~K`%QFDyz zZB6-N9xAaAn5Lsh9+XzNq>7=bA>@2apd2YNRr_*RAs?8s%vOw8wfPt_4ogdf2~c7@ zGn+1*aCrn}<6Ac&4@bN8u|1|Dk>%fXvleTH?M8E@#IEW@ z4>_CF4&>IFdNlS7y zu62|jHk{h#5GPMLN3)Nf0}RWf%OdDa=?DrokLh0+R$1LHlf*;;-QiF03w2bS!Qg>_ z`!?Np4kQn&3ue3HyprM~2W6a^Z#iTPmj|{VRti|ln%jFeZ;O`=NvA5S2WW#xRE9lc z-_MmXpc-?<`>iDd0MR;t@0@;A?eS_tfs?BtjI}LsyLr39dc+xNbtIR5CT`A_ zqP}-ANbKz|RGWCe$4hbzkmWODu?MpJ&wN5Bx|u8cU@lxWQ=2PDCLKJ+=Y>HB9`c{% z4idu^l>;d$ScG4AdDC|@B+%SO37L@Y9$CJ_)07cp&BMC)%k{>ZJRS5UCFIurv6(Q- zKJ2@Yw^`~+Dx2iauO+WDoee+LhIdhnI-J~7V|8L%zLO~G=8BOw?-C%8ce#T_lCu)G zJj@+M&0%?NRtw65s{U{biE8*ZQy>4>SS?u=F1fr~8TGX(lZ-JBB~Np9ui($wT76E! z@S)~aC8E;U`*DG0s-Xn>6*#Ap?+evQC?o>z9LyEr8fPQaOBzfSXYi`XfGLw z+7rn7XLf(_K@We0_0)ydQmeI);W*gjgm8cXa3}U1iZ7O1z#b#0y^{c&*EbTk zPfKW=fBaa^!FnUDgpeI$aH3FN=&N=&XK=K8C&Su*X@p`lJh;30C=mAtH2vK8tXBDZ zsxhq;#))Y^*~>|c#kj4CFWK0*>5}{_q^~A$!)iaANXS00s_c$tWW&sKF6y6UNN~B7 zba}%cun6?9^+Yg_uOF7@>p4M9;(2t$Zu9Zm8yWW>qM{IpK}b31 zm^+0fz=S;S2hi)bWMMp|CX%nK?$b4?MN-qF<@!q$_*?aW=fW4y)?CcdYx$JI=i5O- zRt=)4pWPTe_c1-04Xcxyb&d}hEU-C0Xut2eo+sw#ZyXC(|9fr&N$QIF`x!W#tZSZ4 z^h{ID=|b|{-u(1U)NJ`yC6SJbFE9CNsJQ&y*W6Whd6~hcK4Z{K@?Q*B>_uq)3@K~CY1#=Xc{%4oJ<2MdI;paM^hhE0O|IJ6 zYv+I!xT0b5_4uwI2V~`3`y3d0b8!0xd-_Z)aDno>p}3AzJN_cciTw@}p((F)^^&ki^2hxTf0?(Ip9jt{+MolDj3B%XNecsMo==j} zcT(zN#bp02HL}+&d=yk06YuvYab8v7B-awc7K$$C)MV^)JgNKSOZeO&n27CtUuf%^ zq0@#xv&3gy4Hic{zP&_Ol+u4NlRu+erodo>$$a?|r^Po@t!pC=w!9qd50#}LEKKp{ z0?relvtnlIi~LWcFRc!ks`Kwy@KnIG@iur3;(odj%J!*9s_ZMt$lxW@P0-4f;8zPQ z`n4F`U^v&`Wqt{FH-G=fO3)cp9hx;o2ZNDyb=j;-ULgX*p(@saN*VhR8dz4Gygit(m6*$1qw1Ax^aDgNC#j^<8FRFrsU&kn$e8> zDD!eLyF|GnNsUlTN;uJ=P@b^Su@n_!G$(!OZ(>aBCO!Syb$e_hI;4U4&D6T41(%8zV681d5Lfiu_X zR1%_AZ|wKxa}GukNqy*KDnCZS$w9rHneR^VE^(AaPWs^4U@-3=nH&t)>VBo<6t_dO z_DdzvFEyod>0*lfdR&f@e7iGvA<&z*qGP;E@g+z}d}8^xvEm+H?bhw0m@|;hi0~%< z@u}hI((^zpEH4S6w`^Ny=Vg;C!Zb&aiWV!m4LJiT$6dAR{ki`_2Gt5@k-`t?;s7^cQfs+*8IkX78!IVd@@mIk~$&L(cnFgl2M!pe55KWQ@vTLPbXuY5;oU*BZ@CO+( z7;c6Scl#;ignY-DMM7ycVw0>pgF&zri{!oFvX8H|>lqYO-062Puwh6eH=}M@wHTr~ zzaOBDn(nsWInA3?T3y9+Hsei+7Wm9pz6VFxxbYri$pnxWhbF|#T(4nt&REYJf>=!d z!i}L%0_q+`3+6J?ldQG4AOUC3t>8~J)$!Zvo($f$FNsg^gN^ov`ME-X(cSfm)0*ne z7rIl_Jw_1;(IfxN=J`e(?e?`0H z8}d_&ErP20d={Rm1{p}*G-Je4517^_!gxV z`L2OrqD{Mlf{`~VY*L!@>4im8pD5V2A8mcz{`@e6gc4%6cOZ@aJJVMj>s@I}1`kBndN|b!g(Mylqx^P#8CC_nrvCIC#mD% z{;=hpzwYlT9NgQId`kiDHNfS@H#tLnSn5G2>X1RvnFnMOO{BAf{nOZw9<|XcE{hFn znzRqmx`1Os81WdejXaTpCnF(%AJJTeS|BRU3nbKgJ}Tr=T4+M&2~GV__qOs{ zF=XcfEhXZSV2mu-8Zj7NzU2sPXU}hoC0l?3EGYbKmd;XTOE)P}o_azuQr(`PZ)J{D zSI5Kfg(1t2XsNkDmyl2IgWd&FY-`V|yh|rXpGbJ*qJt8-CjG`E)?Ma)(*aU|AA-lc zog65`vs`I_Ra9#bEpRQ6*e%xZTilZlkO#891)I&?I1j8C{#q%b{mrRM>Fg&dr#@N# zSiPYL&yo{taziv$+>OT)A*IO|a)C&Utw(dbHV<+8@Hf@cCZJo$Z~ARIkv$=LdGm3;?y33Jl<3#> zCC`J?rTBK;a5+6325m%`HzT@4=~jGMDhGG0=|W;F;J8JOaoLKNLG`5I>6@yysuiUL zQhRA?;g$q7%t4rc9TYaBJI`(CpD5gs_}G|dzxSZSjzjlN?}^rKcL2lrp#{lH6?F&$ zuMi@db|)Ru4CX|}$}TOPTFC^J&m5k@LSUtH-~7f{kuf|{j8d&T*0#x_<3i!@@oxD0 zlw0Xl_Q*I$^)AKC{y)c}Igeutqr#6A;F^!kJ3i(6(0!q{e z6Ecgt7T&LM2AZ=0pUZnq9Z9LVIXT^yH-PbYm^5a?(t(jN|aBkuzcO$N<6RoGnfWhUSE8;rC zPfBGs=zc-lrFl9!`Lf7rK5QcA&Np$d$y6I8hjO7()$PuJJ;cPCFLjR7^vZ`sBruW| z4{w8OzIc|m5DyM#jj0sM>g^4crqzm((tjIeKI#{rNM}&LGafi+I4LTNtfZ?fV`)ke ze41ZVk5%`S1av6Z?`1dvI5DQEs;CbqWiH~7=a|mk$nRyiAb9P<2xg5J9i5r?waCtW zvoVxy!Y#U!RUaTMP?(Qyl@87v1q`+ZVZ;2u=dN`mJC-Po0OrKr;t308a_|%-ChKk= zMKEixEw9S0&!78dEUM7Ob(lQSc89IiixX($g{FihjDI5VMpG~<4%u5jo};Dpk%%p@M;FFJ+cZATX2pQs1|C;hh zy8t0dXN-EmMe73Aeyk-u1TK2O8H_VHz4Z1vX-D&pB{ zQ;L%#0Jc}J;!k)GZ{qZ{-;&Z`7k0qaDe>=}$r#o309_$W?s%4-^B;1OnhT35KWd$| zfJaV|I(Nk;FFbek0fq2~t;-OO$zTmj%a*^c05A1X)K1V6-P~D*e6T+(%{Pg@zA3Xh z%Tdb!pg*vp6ykrZ8!xF_f!M4QSB4wu36`RKJ}F z)d>^4p{O48`@N_IOArn}_-;06^>QVn0`=Wm%kEg?$VUp@K@=d4y(WN6w1~S*s zhI!^2M88#Qx{DNR`6;lo3ab*%Kj`EcsLh~>A!H>fH6|~TEM0US z=Osy5Ntw=u*yJDl5n<9QtzgY1k)E}z5w>~7^Az|Y;?Iz3UCz>UDt$@9vH1<3 zhRwxzXLJ&Mha|8pzE^hZus~w^p|}J@t@KE9mC-UuvOV&=3)G=&V<7a4tMR!H=+&vXB+Qsr!}6nd zh5_yQMpiJXEY(~PJiTZE>95K2pM&0=x+;Nn7r#_133dWxEOXl=NNbigwV$Sgz0<2Q z_>hv{G6k&jhaK5nHADjEZ6*XD-dR3}_Y(&=Oj`K1&!kT5Fe~cvzaDQ`qZDZPDi)CD z{kbhsWvha7p0FaicI>Hg))09X9EtCvt&GPL1RAI<-3z#0xOJuKcTQDMf5mQqk2OPzTNF{l%rXdsxn7MJQ-`%eda$#1bK%U6!aE=;Oa82q-rJ!8tQg|6eVY7Zm?>C-k#=?V!au(Cbo|8Zo!R!X} z#p>RyY2q>%4>skRxQ5LRPZT0EuRL{z7oXP!$;jf48Qc|3NE3moZ&w>R$D(C8y&%fHIp*K)RAWKxQ1Xyb9?t7;3l7YT1T;wTJ1Z_md8}noAmQ z#`RAw*pVhC*$2wo>Bs_@<0T|jQywT=D)6kzIjav3`d(i#!FcyB{ZY+7L|FY%B*uN8 zu}W51N%%34G5v#P!ycs8YW=4obC}(Y$z!9uA|UY-s8QJ5A-8{0(nQ>3v_CGok22}C z-6`~w!}QvcUbt_^qAmV#fHzn%%`;pl9~j88@(QH1{anGeNi}l6kahhL&2#EXT4J|t ztojl*N*K1B+Iu5x?4XJAS-8c0ZKfHBHyX*Ekg|A}38v@n*EJX_f+FJqi&l*=+ zT&Uo(4HrNH^N_5QDph*a^azcIz1fC#$;m0YSv2%|k%c4*x)6#Tel5N~2@L2!Tesgt z;SCK9tGJ;gFz!EEHX(&AD)1@M%F4=`SrCL#F326b;RB}ByLH}a{vIDNrD7Zt^lzt9 xqQMIPz1oT#IojW^NE*_l$U&b!3tQBGfLrpim&W3MNPYsnq{S7)eu@|d{15Y5SyTW3 literal 0 HcmV?d00001 diff --git a/localization/ndt_scan_matcher/media/diagnostic_regularization_pose_subscriber_status.png b/localization/ndt_scan_matcher/media/diagnostic_regularization_pose_subscriber_status.png new file mode 100644 index 0000000000000000000000000000000000000000..6d777ff360481930509deb70e2cd9b9ceb8fdc9a GIT binary patch literal 17947 zcmdq}Wl$Vn^frnngaiogF2UX1gFC_9VQ_cX5G*(h?iySt=s<8826xxsVQ@eE{%^hK zoT^jj-uwCXhw0s2tM}~QQtMgIvvx;+Q;|jeO!WEPyLYJaa#HH=-oatLmAw%^z5Qxu zR|dbG;N2zUH4)#A07T2Ew`)QVX;Xj_oFTi^qFzMagqR4 zrzl{g@)jg-mLhCECa(TV8f|j%QY|0Q!;B+-u$z1l_u_;Md||_f`L7JW3ca2T9|~N9 z16e2d6Xo~^>n!{xtJTfmL~1f>)^}NM2x|OQEuRNoC**k*`GQJv!D5A_2A50g2qK{` zdLz}u>tVd-tW;;@?i4TXzf~qSO95+l53k)OFWJ>WAETp~CCF4y-)oFk7-bLRsz(e{ z-v8qjHN_j<*xqVM0xPIMD_>9D8yLFS_F#;k_yUsAc}=!da;e?DUIl{$@ujLj#wACu zHBqk~tcI+(x(u(LMC+cB4b2lKnLpCpp7$^O!C+4Gy*hViVzu`##oI4JSXj`y4?g9&;_u&C9pp1sc?`k!Dvej+3y!FTQv`j(dTWTqgN5e8oa~w^k=t%{%jTsXIc?0_dlh)>(FyW zXH+S^op-s;`%U8usls8mv&o7)jjkIxicBKAB&Nz^RE+}R#%7a$92JG$f`$x#^Ml-Q zNUMHq9RT{)>L}74SoRx3?4dqc_+#N9NZbHb2G&mm&RZ!vaJ!-D)-h@&MiM@`H!`4# zu9qf@{ojE_$&Q;37+0I9=SSYSq z4Ipll5c(H5ZVPBe?Jf5)(Jpg8=UVe*l}q=1Po1yZlh}&O@YkZx!F7nQgnv#y!6F-* zBKo`0Q~lgiL<(p=DK_9a0@XiTkGiCTtFdCCza}oYjF;x}aSPC}xo?uXK87V{3?q5p zIz-@a_@gA>_S{yk@^*#%!#e4H68xqvw1ejll0w%Cp?WQ9pH6?`O+`D{NN5QrL)~f~ zzUX&ML=9ZLTSA^?-A>4cgbSBuacuthu<8VdzRZdpWNmrLhyyu@%^rw@2$7d&-&h^h z+I#29?mjq`T?d6#te!2deqhiCBbby5ELaAOTXiLHF;F~~U6(jXy>r52GH#=);4;TX z>+#&B`n4E#*nKjQE;xT%TwgTZ2|n}w}uF}TKyXVue6s*qs^UYlt1uY?YWr@ zm^O8ECmM35?9zZ2(7KS;#hYC7)Kr@vmyoN(ukvqiw^O8jB2 zhWjj_$@R%fEj{>S+m9gEEbiM$cqJ?zn^@}g4sphXO2TQu1T}7Mjz#zA{Bk{R3`kdJ zXVZOI)bHK9#i4$N|16p6zCm>W-+SeTe!r0vmDAZSVbsLl$6`Kz%05~}S^ z5L}&73V^pMHTc?JuhINF^Sx`FN0b}3`>yy>Myh`I-@4LDuzZ-^RT4B!^mnt9L z2gXt|Ls=^io+_U?UxOgyc6Dv$2bIVcMBG>dt^2>?`!otmi?i3qsA>01I%B`2O-2;= zgr&K@E6jY^8139+vV7^URsZ9ZG%e{JL*?0$?GGGAM-EQ8CSDjRf_BK;dS`0}1n2Wh z_xs*SRyte*c}*OE|GmYT$dBDsWlWJ9{6qCgO3}TJkwx<0v_0?(wMMrA(}5ACd~8Py zSU^)h@LxEyahp0`z;%q~1&93l0p93bDwR|%^Erd`iEqivCSjx7j^O=XpSJq&5gnvF z2NSreKxLSB@6lat*rb5>+^kYWT5hGE9gtjQ!y zXabJ@N{h9GT@DPKTr@wW(t}o_S_b)}y-ERPCW#|ItIh47!&h-IMfMeaSM7l1fDM6V zuBrtCN6`4#jOEBLo<_IcfTe)-v_{nVBhLK{MJX_2`OT?(>ynn4d&(v^Sh zlZ8(KBLX6qR|B3B-A+XG`>QP_(2{(sCD;ILXLqUb+KzWcju!^KxJb7hICOhiDcj!D zmN9i_B4^0dB-x+jFtNip@~`e#1j6T%tt?(C z%_Xqir;Hm4eNL zHBTsEfHavDwkX!yTB_~#yX-3_D_qp@JCVzj{sVgFq+QA4J&tTzg0Pa6I(f=uX5xn* zv6$g^y!Q%4q?FtIU-IWJF_fEzEi4jZkG&|&QvcM|04-fd+89{+heB+eSS%lK+py&b z`by5v3FmYKYyVs3+1&X-*Ec!~2j0o=6y<%be@IH@G}_zPHr%zQXX0P2j8WGF=)v^Q z(WuYtO7x~ItlX%w7wzJcsBZCe#Mm~tFK`Uf)Z8YM&X#R|Q$M6+nO~nX#wPFHAPH^W z)3_ZsmktH7{9LP6e{7o3%fpy4czu9EqY_$v#fiGvpYmtUuPRr2(hd`fbV=2Yj;EiQ z+Y4&3Dn8JuW0sSUXz5k2EAJjR-O{<;Myu><8}JStb5<=}EjvZ7P*C!L zy6Dn`yGoA!ow{*_laQ=zq|)0*pseo7fyWsX*GT0Iv*~i-#<7-yyQo)dn~-6F#K9c0 zT{J7Cu+3A>T*tYceffh|?)7s?y+DFTp0~6UsKS11Z!Zim^0>_@KYW!j z)-Ga2dw<)F1z@0G!!t?u$A>skxYDs>W4ex1%3lwx=^G7_cv@uz!6IL|56+C}9uHJyQDmx5Jfx61%Cx?p6oNoD zBib$@-%ntos}prhF2RcxUUzl@I^Xa%Q!B<@ju0|cB?q{_2aAmYMEHWP$a&=!nhCCTg@kYfu%ypk3b1rvMLa}f%CJQ*KF`$Ofk z#2}A1ly=s^qd+^Qx`bde=-w=g=ZV=&E476ET-i6lVrwk4iS27`EqWp>an^j{S)W&Q zl4vAqz@$pE;Z_7f??6WE;n_;H?qwv#u(Ubry8cRT0R`LcC=KiJJ2VwmvOzAMB6@+2(tyX1&nNLBgc1O$q!d>l=k^rBCqTORv3dwS`AF>f@Xi|eCpe(d2*$B zZYFCsvJ>_6Df;#Oa;4Q(e?b83NKE$=w?bzodxd4RnDP48Vq1M6@suB6Xf?cr&i&pA zB|swM!4hXKFEHDAA#b~v%!UKQutjjIF(LPnG_$16J?I#(=&c3=Du|a@eaGdieLNr4 z*6HJ=!=`#3lV0BZGhO4=@HGmXH%K^+_pyEyrs}@2G?W2mF9e`oT~9_#3zje!w+~ zf9Lyz4)}KprSRh&&Of7K$r^}}{?Pxu7TE@b_9YjE?@PxxKnZm8iG{{?>Mb4?5D4IT zI{In;)*S(BJP{&0d1XqLA7swu;5|I#JCtqtc`wgWNbfkyK060=WOyFqaaCGaJ`{U8 zbD8mm)^3m|Tg489eZ-$w3D@Hp$K%SXE&fm|nLpWmEq8-=I8t(7r3Z2l>>6EhuB%Nl zMwLGb8Vfqj90w#CJnCR@U`@L+8hD?W${txS{-kU)zRN!=_yYJ=rt4me7f0 z!r$khH9n?CRUh#@4uJo_zCte#)9~V6JDI*aEkJnEuj~gE-3__PUP#9lYPNvr`WSAH zA!GY_NpV5PmMt$IS{2nFdcLZ|pl)z`4yx&L?a$4?4~pxh+S`T?^U)UYWICbEZr&E48Sy2b<~eo}NZ;l`g> zR7*Q5G0Q>O=%NldPZht6#W zut4FCLny*G)87Q=SyVMIrZpLf?m*p9{cYaFLb+CdpZ1Ztt2L7=)NvV-76J|uTRY4S zKIv@Fkp1yeNR19zW6~qd4*$KOnaZg~J8{MjZ$P#b2di7rC;Cy2{LS#+yeVnZs0ZlCjIR&wtL+JJ zSP8pZz=xYS!No1`du(3i|GwPb{o80o!kJbSfTTftXur#(f>@e;gu z0f0!B-Z*o3_My>=x#r&QbX$O#!drnmyxEW)w(!O$gVo>>p54-&#e@v-rPY4ENYA+F z&x|FyQz9Clj$N_Q)8?n2@Y4=x)4*IA5*`q(f)IN9m`(3*H{-Gm|GBKij8D9CI z(%_VdessUcm|j3_t&qf@(@48Ao26vk?z_ms{M0g8h7aXX|Cxd{3wSG^@2aN9aZrK3 zCP~BM$b9j&dy_nCr51kpl%NTg7)7A^D?h9dZ+W#O{;r$}?7Q7jwf-ESwk7!w$}G1K>0cXn6VO1Dlb zn`uj-ax_kEC*D#QpZo;CoBU&6)EVVOYV-G5Ubm1`zQ1+d}(W}*&NP%q8vUpiuUiPt0rPQm|TImH>fBjA;ni+$l4cW`x3TgGLFHv@tcab69 zbruU!whtI;Y0lIoKQwuHvgR&I!*(l-gM?b>!{NM*mvGRRziOj9j2$oS&NAj@w09;f zOnjlg;U;`zj39UySKx1juEO?^xDd=aZ3&A_<@g%^zdEb;aIu&Al7k2sFCeDY+IM>1+_b_>d#}By~Wse#+aJFLa8j3s@2C@p6CtekxB4QnLk$f zyz+k6Ehrg$47Ys1Wtr7o>Zkf3!kZfeQ8;8mI*FTI< z$gk~0}P#)t=c$DrO+6{m-t@-Qnd z_<>F}9;lB8@BYy@7_8Bc%d%sq3qP*zy8GU>OmAotn^x`nQ@>M#qPXRULy^m#-1k}n z!v-VI7?Ap=x@%a2|joON81xT7^?&IqhdT?-^NK>iT9yzs04MO~)wKkv(?G z2xVUA_Y$S9bpiUkTm ztbG21-}rn~LnNP!jr>DlMWJxpf-823N-joJ;OmWmXItl?#-X8zQh=ijN7m^!uC92@ z90}!dGR@jo$K=kh4?he_@3L2@j~lXY>&_Q1T2t%GNc*#x!Ph95_J@UyV+@pTk~d1H zUp%Qk^g}E$Qsy+CBq>YO&p)~ec=mgr#1u}K=!PsR11`o5w2iaeRXi};8eaVmH>#U= zFB@Ybh}hER~gDZod7tN0;q#C%PptZ zQ@e7`HraG|^Oohjdvy1GqkmI-L2M5H=|=3{)W`U{$X6P1fHOMtlG;E+D(i_|8vb%? zlrQFdgaar0O!qO`>1D;da&AYjpaf?s8aVe6Y?FbgJgqK(1x2pKiYWu2U1a*`W+++k z@3?2sca-2?ox8WKQByW}Aj3AAW=nTM5K~KO$x7`EVa`EJT8o9C;lSU%Y&L7gNEv$S|6}X%6+@V-PE41)sh~G46vq zgkRk*W^D61h?jL5#sl}yJ08pEUoFuElfSB^f|CsOpjU)LBU;?4tHyr@NSg>RMuH?d z0%QnrrRZZ|!3DIZezU*PIDR$mT*1ITdB1g2j82pY>3T@ zU6I_;KmPD^q(^7XME-H>zAy98F}GE1(*OYw zH5HcceR&duHbh(cNKgrY6@Re<>ylk^iYG^a5pYNdF_c zxG}GZZ|~=L`4Dk)Yw&k1tad);yCn&nx?9Y0Gvltm>U0Gjo4Mo}jP}I*8OzTkRJxlRqE_E%2jl|;4HpjceOdpgOz!L~`f}y=@?wE!^3T-CXaQfVK6@VW-3sEGJS8$T1#QND zab$40Ll)GjkxBT-K{ye+CCHVKhbqJ_wrhk3@l8{=GcA0385p7*U80NY&F<1Hl4Qhj z)gZf*k;Eu?m-A9AXLw>ab*wb#p4-|vA-INwned8vac^`gxw;!vY19cGVdfz@Kyw2ePyKq%V4gWES~bUSjo(8 zCtPxEfg#`;0y|r-0D4Y&(Eh-~>Ae8-8y@sjwe6&nOz%JO>;?5Kc*!d4>8iQhhM=EM zwSJLD*^MWk^1uUgA&CQ)VT5hrB8tRInZY!QfRIaBG*&vmCjVO+o4W%ZFFy5Yopx%n zziM7rU=wGGZ9FkuG^-%9pRT%ElM$bxw;R=RTFcpa`Z$X! zR3#ATvZ`sD#{`7OM*&9FQ@C>3gaMK&KVw?g)de&0{9 zZo*3)8)cCnSG7a+iJQas066^TtN8*31cz}AXozW))9CC#igZ;)-`BeKx@|ZV?_E+d z!q_4v!f@CX#p8Nig=OakEYo0(3OdGJYo)Uqop>XnG5JO=`}vn#MRIZf*R(r%5tk67 zOF1(5IIeCsIW#R$_mx{w&)4~uM{lLPo`9!gmf*fY__P#hP-5EKs4?oYAnum~rgD?w zT#`Svn$*=Id5KZtS9aW#uLh*stIxHm9OdIp93BUd)Xtpv)Z00_x@6<~pJDr~sI)n9 zzOUdjjG81R!*mg&C~KuYnz7fPLS zK74~L@$HAF2`n4&xG%YuXCIBEuq=lX-OOdM6X>kva)L~hSNHZ4RHL&i>pNS&2t0qR zok+yvO_4%bWsWxpjo=Uu3m-RU6O(FPd%6^o{hwKIcy_)#$>z?Wf`D>|V*&WcmB{8}iP{zsasE)zKr@Ks*9G14s=`+Z>tzpva<_^U%uE;`A ztrM4!=&OLu`z6EgKJYjp^4~gH$rcqX*-h3ezj&-ap6*VTvGgBq3i5o%d;f_WqH_3U z#f5@8mtTgK%d@=jxver4^^2ynF4juCs?R;-V~#qTv*z2}CgZp@aldBjA2=?^ytuh2 z_9)JqCA*|lv<@DyRl@PD!B>8AIQcg%j`iD(2FU}T^*uMALQCLxS~J^q!ZJO2Oj~$+ z-*w}L_qGw;Zy*(86z@i++1qNB%{d_(?I6O zKj~YtfTpFd>yhC;O_E5}*+Uo8bi}S-7{ZA?MLZLWBh!1+*7p>mapLZern)R>0;ZX* zQEFAh@zDQd^-&>Nkgc>173fTOZ)_%)1@Vh)E78`Q=F6M_QK;0LMgm$SM1WQZl zrVwenpJEKG2dsqp%gm;!n}Gb$c&5r?#N?e_U5_Kp_IO3N{U=B&IHhQBtc+m?S2#bD zDLR>=!J4&9<ZJ(LM~2j^+IN zCBEOJ)WE692Oc-syi`FxBVU@E+qFu>I9^C)1RqsIS`u5M)}>PY*0oZH5kxQpk5y!n zcn|#^qbIp}20iUfM_SqKQXne|Eg&3#@X5h-R-1E2%7d>*D7RAsEshlmOiDcv3}T|F z&z_a?5P4%ou3UXR$35 zyIq@|%m3$_?}=BvB~6?RciI)jo6JF_tFL_0UBju;v6+wSI}Ao}S;S6WsFQ6(!MLO! zdL6sXAf09&6__d^G)am;Cv!ALnKX7)EO^6sL!9`}5(xr-^493&U~JMm>l^Iu;DsGm$CN*ycdh-7jyA(FmU}I&4^V{u=d4IK6`g z2@dNqV$;?vH=OPu=ACdlrE1dK&!<_Sk{MzR0nGxYl;Dk?14uZRuU19qX4y{WwG$y) zd_ejF-jG#t%719(Nl2J7#S2MCm7H!0j1kJ)gFE(w&v>!BFr}LvAbHiPa#uwN`=7Lt z!j9njy*CWE1tg<6e5%SUSQX8v%|B2wgfmAeJVjQ%(D)khKQ+>j{gm&ZCR3E7QP^#8 zv14qGjk znHTr)cx3nJ$_x+R5b=XwbNDu1^1^=|y}$_`1V2WEN*=fv&egq5X`>f`(1;!H_29;j z(C#NRu}bl6RX10!dnwVZ#=J|x9%U6LjjE8}mvX^MXK&2i#83 z;vkJy;ahvW<*jRfS_Bxb#gt_to;INkod)wSy=dbAl>5~8jl5oe)LoA#=27)j6fP0L zw5s2+-UO_MguR?)pngL6#N}1@?sIyzeD?Z|Zon=e-BwgH-YDSVB&Cy=F6;H5(`bl` zXRkOBhvd{>z`A~G7fwJ+V=`RJDtTHf%;%Hemsg72QWv5ywnb?rG` zO3?Uq7s@ecAt45RYy#(teG$BSh{&)%cCDNH_zI=-&P^18*Lg8PVJ7QG;^A&)@V?9J z23^BO)gNY5%S$}}pYShsDGTe0wQSnC@e6N!6<@8JUEf0Iw`FXnlbvIHKaL&4(Y4s; zog>U$lgzD^b1>*^l_%+jM*)lI?{|p9;F&>`UG7lRq1&?m5#N$n6Wh<2gTX$#A+}E5 z=l%ShvuVL4p=uI`gZ{B_Pm+T`Cda%4Oh!997_yPYuLV6EB*9$0o=;pyE@y89W~Ux#9LgEV$2 z(%FVbFt9z7$+n99f-di7a*`WWvNnEPwM!_;!-32hR4M*q_?9FS8nF7?QA-9t$L2n96xRb{!$>mGGQqIUxoeS<{UTmhCd+{bbptMP$NOF4fJ~*Fy&4W5b(^io!+UCyPv{;QjbZXjR-}S)fKtdA|jnz>U`3ojMJNw z6hv{_ty%q!#AUIlW`~i@_BwiXe{lFuf+Djk#z3qi&5Ah1R&Wa;50%UPbkcA=xQneu z$?W9y2uT=|6>|KwPsJVSFL!FCMXW{a(s-Pj(7F7S+}0Ua=2{cI4EL&Ad1e~7$OHr> zxQuO#Dw1;#G&G{f{KNdiu>Cui`h#Ksx6dOpk1_E8dW!_RVVn#bVch!<@2yt2?k-s) z?lRjN-9Lvvc$M4BeVhjy<5<9ucv&|h4Q_46ZSmf@c4TmPu&*uqV70kZr!{6F@puM8 zf!3ULzV9Y9Vtv84-;9lQQr0EK%4E%mtq;Jm=eBbD9JP9)VJFcf zd0Y`XkF7)C6Hyr*p7Ij=nxTpo3mZ!W$Y04Ih>YDYS@A|%RIR*le?OIsb)P`(9rFkM zkL@005D)ku7KfE`kxIEzo+fnoMjuD=Q(8;kFp{d<#tCt4F=u<$UiV1dbdZy3It^v} z3`0BD*X;?Jv5T$^`5}yAQ^dprAa(RGPv+DgTGRifL1Rv(U{P}%qWgA4$oEihv9YEj zvtqX0q%_}7!H0uAjB=>A7a7B2GT~W(&DrkCSUNX}7*udFBOCT<)JFHl`o4ByZ8<0# zKy`xh8JgODAAw-lZxa1ggP3d#$hu*f31(8s8?;FLIvG&1^OV{qMv8>A?LwBSmc~+K z>s2Y}mOvd7MfMopjLeBxX3lAI{EY2G!*a&>@(KQU2WAz=N{P1g>kW9scS6>K)kafyS*k z^+HU29IamWe+u8RQHKAKM7*}5&lB8M|EDG|%d6nM@i5ZZ>Rq8r`DwJwpo)$;{Q!(&vwVV$QiD=JC@E&fddKc|IVFZlz!mDj-YMb5+N z2EOfRV?VT*x2FKG4{xK;qn7sHDrb!v?>fFA@pY&6TP{jgb<~6UT*Gi z%wi76P{G=By4)qq?`I7CP7w{&HgPAHQ@;oBZ=P6G`)Ok@GOy4tQGSj` zo6hf;wW}k!E3*}*ucE)jx&2f=Zf&>(&E=#R-tA*eJa@-;WotKGM4B=#M+|Ps?2gKa z+L~mELk)K)$Q6=gES8Spr|R5K0S{IjOAZ-Wtxc}wAClnb!DQc+XV~Fe_Z|sI4W~$A zgC_li6!vKoIZbg@$kOB zKc#E{z62~_5{zIcBb-X0fc*26Lg5j5_I@)ltO-4Qoc|e^_fU$Ad6JF%Dq)m?U7nJW zm^z}t9R1W_i?3e9+7i~-kdN{u0>5$VH^CS#X^!lRsZIc;{R3Vv1keX)GP|^$05zyg z;zIlIh6?;c`mDL9@^K8hMX72&-n)Eg=v4sHeoY=#h!IUvwfop)})eX zl^LAe8m%m?KaC4UG{`YUqT0w8mRO+#UlZR*0I>bS&i>GZ?8{WP)=g3~L%IMEiRfX3 zj@z8y7MNpiWA0uo*HBM#P4lL(Vvrgk#1YwqgQ{_m${q7sBfwmOo-S%DDrE}!{`GO$?3Z&+heh_tu9<{`_Ur9Ra{*!* zN_pTSXjd}N_rc;uus5-T2Fi!*^Uqgoe1Jh``p?B4_$`HIO2TXP#O2!UDgTMap+~6b zi^w3e<8ViCH~a89QUg_>Nj@(@lSYve{E6|%(W2OEBcjHZ zx|FY>^+Na9ZbBS2?1nC^p5jq*k@YP#Jh%*jz`>THUP%u|sN;T;fXPh{%Gv&k7EkVF zm0R6F07Z8i0y>tvyBT}OAaqGPC0MfdkF1Fyu;AKWTGH>xlK0v&ix<;cjcB!gOn6kW zc#!VZ{DtbMkoE3o1x!shXkFo|WIlDtI16KjuvL&^EI({;+k<#EvThl=JKJfTibNt6 zk`PVo3Ur;zAFupq^fHUHJ0TYNZNi^mB0`G9Z}j6xVijeb@^c1W5D|l_qp(WNZSCdg zv?mJdBb|3Bp3=%f2UqKqi@xyQ?x_S2>O5~8>e6!hSLozAJY>#4YZHM(XA9>N9FkOzCEcKs1^J6K_g71V&1oVqNBK84iLPR5 zDS_nONlhK%DTczI2BwH+Tjizy7j-emv(@r;-f*QrWlFy&_^`VhHsCh zfQYKEX)#5@MPwDgHGM}!F_jaQTsgMdGlMZ0u7Q9v(wATQl8oOi)0<_^(oGue&N`aw zv@;BA`6mWx%~3xWE7c5YcCXz#7pf0gM{|a9+#zM@G=^D|>hu2VEzr|=v4&???}U1k zT{$X6hfv2?n@lurs8aaGsJ9vOeD1I^{`mhI`ZiwgX!ePCe}O%AnBgEqBcUn1#Up7| zP_7TO4Q>lWq7}d!C#gYIN6Q~NHEPTz!f`{a!Lndp)QZbHjn0mx>|dT^i7W3m<#)_X zCaV@XM15Po{9H!g9-AAIAEs7r^UA7mkDR%`U`(yk1WuS3mfSpY5vY&BEmrbda>Q=b zL0a@a*eukGDhqXu0FR;K4LbKXV-t6^LE&^&z;cPbA;Jcs4D|t+IphLQ6!C+vkg}!z z2I9?62icm>dzG5yV&J7B`lJm~RCbxpaclDCp2pwk5F+k_(gf?K%T8p;_40eKJ&!zS zQ`!`iul!}F=8(sW>~W{j-DF6mv`|qO7G#8VfVQ7WcQjRRI7D+DRsQBk*?At{ zPH!$%plsct^1p&Y{98CGCb8XJ+Q71>9Df^Jtw|bq1G|2xSGzg{t-!^*`{_nO*{Ks{sl4ykfPcZ*~6Ept*rXsGj$AP1{s@Hh8H?&Kx z)&zinI}qPinbhq^tanw~H4kF=l4_~1pWpVxj26?ZiNkH?davIHr%T@dFzE8*d9zSI zl^AI-aFkO^m5n8$`v2Z_%x{cx9>Gwwh!8&>8#)*sYpC%B7jaxGkv9LV_hJ(%nIt$X za0Shk!_k%8Pc--^xViR!i1sgIf{DK`s7{}rkyzHUpf`f#K}d$OdTpi%_}i+D=2L)L z;mvC+Uu>0a2@b_zIx>)Ne}|k&+U!{qw82PfQ(N@r zn8eDO4>ukbv$;gbC^9w1WG@YK<={lB7Xv?k>z-R-7WTC#x1#&m9PwMr`PjKX7K-C|N7R%+z1AYPT}b|Sg(CT#w~+BY)0Ek`AL~e;5>=HW zbX`>a4HBho?c{s^c4>S0Q&n3@(j`V7JKiOgd5}jb?%#7|sA8C`;!Ex&8XOJ&T}#gS zeDoeqg``)AJP3NmB+*NErYByD84QtIdO^N#49rWd(Bj%52dLZ!!?f4!=d+^QjJIaK zr$i@qDUmLwSZCYsu5cuervFHaOj#puEg2Z5&U>~LHA(kqa5N|P<8%IQwnOv@hfl5c z6^_?aVc!cPga&)V?Dv(XRE)mw`1m->pi(OHhaj1L`>)XOp^9|hE^ChJx2G-JC5$aenKOI4PVx>9W1N@0cRnu#@J*KBW*Qw|(= zGaX}b*4Zya6T$-aTt-f<-ZCI)+hA$QgMonIZeoU!eMZiC}H#VtG4 zF(EPXUb}maMUU zp2uTHzqC>RhQ5{zxu-}DHwkfR@Na1txKjeli6yaK!4J1tu2A&&jI}N*ihs9fh^L>a zzD-GBul?E4P2DZ)`8biqSt@3vEB7fi!?by>^0T{70Si})?>?`2g&zbDpE6a zQ77|_hEM{K&NxlBogI%~lGLY;XjE0e^zDDKE*-Hi>b29=5S)1?m|%)StL6-Xa;<`7 z>O@ORH_SIvEVrO9Z&J<2C31&Ky?+q$uTpQ@`u>Eu%tZV)F)6&k{*c+YkGL?Nmr+M* z21yMSRs->ku_AA7{$2iFz2uvNEYJJ&LBu6*Wnddgq{849b>4W4f^9*q+wPLUQDz+A ze&rdr-mSZx;68&D#nCaq_3!l69x3 zDKqk|ao@h}?nCD36L&MIi1i>vNYI0j;GAC!rr7yrqwM?7K1Mq|bvwRi7q#QURn~g7 z*<LY>bC;>2UZUY+JXDPHk9oHqTi!Kkvh5I{yp}Slf4Xcw}C;C5t!ki~Wlq z-DWwM>JvZX8hu-8jrh4Z@ljeE`kFfim)P^BaQ`M#kB;$0L8n6%$z# fRIZobnmS zk4oF-EH&MpIlU7%588#?g0PmX`A;v`1cb-&+_QL7#mDb`Pztwjl*+#XQa{yN1k7Da z^YT1I)(PVM$r(XKdcN|T&u7o zR+wP!OkF$hmy4xxH@2MWolw0Etm6_oHOd!{yteE&`+Da+Q%0K~nZmpF@zlhKwqhy8 z_-t+$|G4u;Ehz3ME!VTNZX_%VzCpiBPFu#fKfdZlU_Mf~FI<=Q*N|12ofV^gu zSWsN7AVHtt1>_g1!+KzH#&sQb+D({;vr+cD{G0JM0@!t0dUrNnb2Q1Ro`1#$Lo6rmgXjE$R z1;$5wz9wVIcQYlrG`epijDuRNhZP67{@%_+>v4xH0NSQ5o{dwxoeSfpU0k24$T~gS zKbXW-gsbAAF5$Yz6I^`ZAND#>l%(hlB?3YR5~=z4gGI?$=+VF0#+!o*R(<4AtSzp7 zB+GcUic|%byuk&QgM?sO2aCQ5%YF>;;tADcD9Zj*&EX;i{wMkE1k{xofg~HB^uWwB z&l8*Eo>t|K-@$T)DdETS*j3?e5;_mF=z}PxH$5|68-LK#7)mH{VT50?eiP-#Wx&)5 z1B_7+`PhuMBacZ8cx87a=$v{laoFu`_QS4pgGe#)r(}yY5dK+7QPr!s|2p8@6n-L1 zz-Lwn2M*S6d(3}eaz4xagRFJAd59|~XG5U1uCJOLVhA4mc@-I9*}`&&I>3HVtOxay z%INU~Fd3+dEjlYg&KbIwg2S4Cb*}e+KZ{m)MMj?zUk)y3Ga$>samXfM9GLu=P}S*| zonbd#?T;fo{_TnCzscQ9u^cRzwtlbuFTj=D0gt$il9&S!i>+wt6fi^f9;xc?>G&Dv za60^9{m?NfWd?jz67=|8Do8m0LK*H1y@XRv(%ky;VN$aB&V^lTjl4pChWhiNv|F&< zooegMu+K`i;MJEN}R zQgpD1SA}bTRD%p0`)H$Eot}E-K}w3xiXZYG%xL6e@z3{ly_b7LpbP|gULWz!p$QRflyx2jlAp99r{_7o{EE?(^qjKhl<`}jj% zZ%^{pq!X>$VkjDk@joD8%}PVKl~YD7$2FB)soA2F^dY<7tHtZbGWJUy=m!UrE_m(2 zmA8MA=BmrOe;Mcq!%c$QE-N_MI}9%{G>TM-ym|uM%$$in=G}H$->%)}yt;PkGTJmx zBEFl;`MP!AVPc^jE2XB;i>{`&MuD(3$Rk9Fg-^*MLVEZ{h|6b%>Oqf5jQhUwjhfz& z|NLk|-g6(jl1M=Dql=PU2*xB{bKOz{f55g7X36Sf_W(Dplo1jwd6jsU<%4Wz|9%ti zbL-xA94*rSJ<&^3`$;P=wF)DE%l3Cv?czjM`=j4X)8(>D*PWS^jqdd8 zB8>c>qq$shL!gO0kL6^4aCBHv3O#qGDQBjsU;}#PCz|F9dsm-hhbucb3dEO&s8ieC zq%H)tV1}gA>7WzvNkmY15ru?Q{@3S%_ImP1wuQRzOjnl;wZ*Fs7{^R<>cyuk>*B?M z{RGD+Btv2Y1SsT1(l_&;PXeh>f--9>x~zJR6b%xa`7w{Tn_L*IDZ{*IB(*e<+*v4& z%1yU$MBrC{F_}w_{KEX(I)`ko#V}fRiV?7#B>V*fE{iSLE-x6FVXE!!-y#RI|1!S4 z@LFNJ(Z{8+m5XD(VzN8wGDPyo!ZoqpOeV3N=a-;iH@b{)4Yhi2{YSqFOqx6eU;I9| zeTwrxeo99zNKIXa@7-y}Rge}h9{oD+dS=+XQY{l?|8~%A&CHOKnbWX70T6cACyx!k z*w@stRf~I+a9IXtG|*I{$1EIe85)P!$$8jM3;8FJ?1ppeAlIgA72?@RK{CDxFWnvgIzMJ+hj}Jwp0^UD87^T>z zM>d>0QC|H+y$Lw(PtyRss3)RO)BOJtk^^o0VB=|jq-TKunflZaom9^Mn#M zoL)H+L(*;{CGQXx_34XQbDu`m{5LV}aSL9LxQ?CgFM}y?8g`HIgbaZ9*m;<`G!B_l z-+|YAFTk~M4c^YVgJ(XUjy?(ikf4UcZ6^o&h%wgbHH~q!6w$Jk=Ftc7QPjPwNOIAI zxujyLdXWuN^Obf>u zNblK&6mpTecmz_^$W+R!bksO2o%(7L8G^jXSrkZ6b|v5N;WYD$qg4Oa*819VWfv_O z8$&&{YLd$YQaHJhZ%7P{n7fsJwY6_s?!8CuO(78h2N!>*yO>(vmjP6-Z zP-?UIXEhyO{t68Y^(JRgLCUT^6gqe^W&CiZ!E3Bkx^Edx8lWe4Cy_)a57NgbQ0Bf; zvPxEi=w{AXa&gj;u-Sx=tt?t>pI_dm5d)vplClAQmH*C0INyY0a69 z^yaW&a#yR!#Xp87etPiUIF+P^!)hBLzKgJX{bY2P_|$%zb@cWz#u#G~d$cAJu%ha>b2xjp<%=$rKG$1_ zlRiuxy?u-^#+bDJ<%xs~61LYML8@{xAI#W&8#AP;C$)~=z9tmWOL5Aw^uKNfV~nv! z7%#Fj#u#I)-CA9dFdB^yvmNXa!Q+B4##lqGP9*a4^B-a}*rS5S1!Ih{hML7c8Doqw z#@dRnkzkB5##p=YM1nEK7-Q|m6A8u`V~n*MPb3&)j4{@3e*;R)t~+08s?Pub002ov JPDHLkV1hdLtsDRV literal 0 HcmV?d00001 diff --git a/localization/ndt_scan_matcher/media/diagnostic_scan_matching_status.png b/localization/ndt_scan_matcher/media/diagnostic_scan_matching_status.png new file mode 100644 index 0000000000000000000000000000000000000000..2687db23d4714b105d656592b32e20dbb90fdd16 GIT binary patch literal 74021 zcmdS9WmF|Wvn`0zbmQ*s?kP3@9EA8C3@l@KGELA^|b%ch@wRr<|ONO?q1c3vi>2MGXZ> zPytm`0ks$e*4G*G-#^jkBSrt90?LR2O2`s0n13S*-(?_?zwRRnP}9DX{>O-l5l!N4 z;CRHx=uO&C-AU-Pvht>OpSv?|mZ5Vp)^u?|#uuYP7WDuq3yJLNpOZ2gk7ti7)%FO@ zedG_smNS_ut%Wp)o z+kXt7ErP)S`Ezf5-5Ydvj!TNY2wZb`Dy0PHsQ`Kmz@NnThyqbS>B>{GZ#Rtw%^pfc zPC9FFX@GV|3$>oZo6loR#Gh_fJX_l*Z;3yqe_!BOn|-b^Bdb7*!q*fwxL2q!@W0Qm zi;j)+nWIc55|b5DVI795ba<|!hZ*7|68MH;91iWhu*^{bw*9DDe5K~7L)g5-TG+`P z-`|q@#x^aV50x3M_1qIQeKpZOFST2>ssAV@^+Yj6;5RJI?bX(V7QBfcoX5wZ`e4pQ z*JUOkS;DMEzsKkyWF5Y(8lG#iq*5t`%*+X}oXhh(;SKO8Q*129EEXafXYfugz#TON zAQ0KFO5j(h`G@^xurgtB`9$7W-h&&4^A0-I=U=JH2}<&g6TF2_u&0}}(_E&PR*%DA zZ-C_Zw5#A}4V!M!ZOtEN*sf3Q86LPd2&cvlip_+K^h9Ke&e<*Wm9^RprJRam~{|FpGeE-L+vde2gt}IdXk^K9|)2sR``VS`R2OPm2&3 zw}3XXa!Z!_AY#pRAv{tMJJsB>(nw?;db|FUQP&EIyjjM;;-WpZg-L4r?8gr$h5XlK zh_4lPQuj0c2geW{mcV0atAg-6s}+Keln4<;QvBON27>+vlDMkMbp6v%iE=c3Ky3$P z!(w8b10CkgMSfNDr1-;~4Y~|EL&W0o@H#>4-k3>UkjMHTcZ@=@7KE^l=5VK&sZ*)o zUjiEw=o?^#<_oUmJheu8tMgtfgApa>W+lkHJ@gITC!y$97Oxekw{`lru*4O8XI0YE zQhOU?MJWmp9xHaYk$EmHl2$T+ZUq+3dN+vJ1!~E-P`vFw*t`!@*fp2PHGC{5^F_!= zf;sAw>|Xsmw+HEa6PJh)w&_Re>EqsI0Zo$pXP;_~;iL_2KUMm{H|o-?pMsZ5&h}+V zO}D*VJ7n*KJGDl{e$^5%FP}C0XvNtZA(3z^lT0j!tnS9>nPFM9WR9k+AJeuudvdLE zRWO^#3eVFj`&u&8tgos$N*}HC{!L&9bl>1CS0s1G(etxocl+Y zo9X_ez&c5ZA1p03){k$nfGBLImG0e7MvP(Xf|Kb-4wV^;N{vf+DJI)X=u^#~h(eFl z#ww2AOk{?BO@mH1J3Fgb(MP$uk0`12S+9IYM~WcFLpYVm@%!dz4q%c({oa!VRI7>u zesbt?r#hoJP9Uzv<*4*L$rl^@Nd}z3B_VWc(U14Mis+i7QK>qLx_fshiOd-(a0t{X zyG#0PH0w0mZqxI`k{-~WL8TfgJpQf|aZY&b*{1BV)+LEFp^MkSO5fJiW|07_Z5BI? za2P)%pxx{Rtlq5F5A32My}zMrFg|)}bom6ny=}UkAR41hn-G}VKrahosjXA%!s#X3 z`f5|rq<9e(t_4L7Ri|_|94)Z{v{$R{qQwFI$(6>739$#|fSiK#{^EnMX`{Xyw0b)W z1S-=OiSyCw-BBqQsPBDTef`9s;9hgzeENhNV&SREd{4eB|Hosm-?DWYTIiNumS- zG;H3oiu>V14n(&Y#AD;R@d*$84xfKk>m3F(pD!<(k@fFWmssS&q-ze5$YN!6DQSFl z$)vkAXs%=SZrooBc9ksrXnWiq*Y;J6elD8!jV!T2=SvFr?f?~5*xk<+ zjs(TLdQs+w=)`t*Sw;xyT7o%IQsE_p2xJndYs>4pK^~Dodyy^MbD|8B_;wWd$TLks z{Ul_Dszg}(v2rZy!DT-)8*3xgdTj*KsDB=Ey*iWq(AHeFn)6r+w)|{w{8I^`2^hcP z3=QKnULRGjdumGLGQGDPFRJy@j8M0QC9S$Am+CxYA74b-Pc&h#+vL!N-_X{1Z8Xtm)6K_Mp9d?DuT3%(*fdw}JmbKPx-7Gr3|OoH4Y-^`(oT2o_4A#)>}0jV9H{XQxsgdUXyczN z(5O;p{i%K2?&osfTbg)8y+PlAHNR*bn3CRf+`2rzJ)`q(RdK0C2hd2*)E2wcH5{}G(XQJIo;ef%i7{mv zsKGXY&XQ462wvk2oGstPbV>0FG5?{~;Ic~lqEct7HNVjuXVkQQVau1e3hU714T(gO zuVYfrMIX~zHQkKYvGQT9R}c-UG5dAa`<&&DtZfXiBgsvlidGU;USII~y9>Pc%YWjC z34fmT6nV~*x9o&$r^L*c2aaV;e`Ka=HLBV4;Mo*b-$;a-44Q$IlGOU+w5++J9!$sY zX_rH?7g~GEvu0WOmZEHudrd#=g%=fN?LF17O=P!4ktn8FEJhd(4t?128{WI)DLyhf zK4{{awW?Lfr3btV)jAseMI_uK+@9JF0Eg2mcM!<{Dz1hQ4-TXEhs8OlmTE8Ock)}H z7K(NCH^|=|jvel7EOGViN7sge-a)urat6YO&G!-bwoZz*Nfqm#A<%XV^-^_Y;z>## z%IWFre=qA5W{@#FSaNr2sny@5z_Ck{Led%@+))v*e=50+A|0+fi1Tlkk1mofq)wtk zk-k?H^gW4`$l_`Fv#1eo!|+&Qet(lx{VUo*bYfXv%!T7zo1AMXo-R4t0j*H~RZ5it z^{?WLazuo&Y*y4dbUf4Gp!TOo=(FK7_?cs=bpr6^^Cath9eLzn^a1vAJ36Uh>nAS@+ zRig74#1rxb-aQN?THr2$bObn1j?D`vFy+Wh1t){#bh(Z!Fe%g2q1YVUKHV)*$TfYn z=a0pUev2j#?a>!3LchYp^f?Htxn@&Xa7fKs1026=JJQ&yWfk4JBi?g>BPYm^Ue~Er zEPNIZ>Z}Waluv2x>fOgCDbB$Z8$sY^EEDBW4B;1RLS(^M!Y906109knmpZ8P;>?Z* z4$ZX$`0tf=na|bH_qpfnD6R6of)cJbk)zlxhK!ISK5`qgbZWyano1(3)jPp7Pqo>F zEV#t_K&Fkb11pFYMwbB?+0!*iakUIcK!{Uqr=jzJExBKyhqYSGEb6-mgJX?z+W#Jp zr-_oNmmfmxFyoc#bNC*A~X1KJnpUZ!jiZ7 zdoHw@e6A^1R1erI8MrRt8~MN-tW+L=VLRcSID7AW=_pUQr5-5vd|tU9U*ni)z-q0N zoG%#rDIntuwqZrc%wnrEFYh+a@9*v=d6+C`+9V_~m)p)s_JPDutlBii%jPrP6FNe@mDE0^$s4&kWc?%1L< zh{k|&rU5abXgz^%Zz64Y6`fR%^kLAlLdIAU4x82>uGp{$lp9AMsl8F8O7v6F^h%*r z3;n{v_f4?YdcwqD8-qryk(s_}gZx(!Z)s(b`ncHm z@{aum3JWPFhR8Il59Gyt>s7Bx1>G9MoBPB?vWaDKu|UZ$R8=epL^x>qq1GbNj;q0| z$gPZkp_i#Kf#0Winom_fUM@X1JT_M?SM;VL{rw9)NLD7H5sQ3eYpA2+psau zv#Xozuyh`%&az)>Dl~-6qu9(PDndUVlkQ!tAd}ac4r@^FA@$R&QJLV6M1m6%k`A(J zR1$hI_>c{Aq-ng=%|fSALFDMcrXCdsOH-4^8Ea+){(xCoXsxBgSv@tuqI_vDW^fFz}8l_$4e#3{aXr>Wv$}>ZA z+zk=F0Xyc64y-`gQqCuO(8XLk^d^%;*M_FaWn^vhFMydTtq63;&Rwm zeuX=)M?BHCN7nc^D2%ssrx=+k`8z*0iTjq7>+#=G=*Kw?1(bknySlx5YUT9Vuw0iO zVcAj|r!=BU~ufc?1xKx=lxHHJn-Vy74%cj4hM_v?7gc5+Kkm&Nh z-ul4QEOv;)?)bW*HA(u+P^S7)Q1gW4P@8BHV=_w4MlhT^-uEJ?kan{o9|g*%?x0oM z^JY4S^6@lwgUZ3~jpQ|QKbrgZZHo91El?Fx2jXp3w?n=r}Ro@0J z8~{OT-|Bk@mp#{`37Z>6sZ1*n5B}|KZ@*u`1z&D3U8{)|r%!_5%SiHpAtn(9z0+zoZ;De)wMs-$86m}|ndcv|T}zwp7H~??jrp2J zg!t?@y1@ozug8ogwz5+$wHimGgC6P^*3ZoA6GJt7+czSO*?*zQ>+hxL(`mlu2MEZ} z`v*;xKN%W*`^!B_QR_V%ZxtAmwO)EP+!-{{1|Kux_$GiVQ3QOBYgWOzetVNv_Pnt+ z@p?xih&ldw{Z24ft!n*3&z*SGiCKg4!>z>J6g{MSIKlnBJP!(;`fG_#ur>%}dO3W) zbhg`KJM%?1@*3I6H>m{mrw8R`6QdmZ`=Y(9&Ic#Iz`gO|E4K@Yw{unAfI{;bN941b zN#x_*g&U6JUwp6v9grQaj5~D*Ebg9%hQ3(PJqJUob*T5v`p&mxq!rlm6Z`@2$Jcr@ zl_ruxofm17E?&Zh=GPk-=Tkl^K<n^262MVd_Vy3UagQ5MC_;Opv!nr4+jyqJo~-;>{_Xk(LG1)u&}yS?i$0q?0Ys z$f(QWc)2;wbo#?tiko6%gMvgQos9mpVzCM~NUW;W>)uwDj#eB2!eoV63tNIzs>qZ3 zI|o4wqOeKNSVRWvq{-Ru(7-d&IwK`z!hhFUhM9a%<=>`=q?cP|%g={+R!daSa_Ht= zLE_K`WLABlR|WfnCsk5wXI~hOHtBIJQ_-H62%B|bX2Ua#x#FTsR3E#7K^*{D{=Y8m zTi^jK>75eug-@lQMg_dLT00t3m`OQlt!)pbB~%Jxp-HNT;a0ME7i%9T(RB4BqWxuZ z9UEDq<4B3A0 zJysiooqls;T{@}9D7n2h9BGt4GO`uAXEIX#0U(O@4aRJsVbkFHk==+svr72X)@tSSCuy=XL&{KzIc5O&)d3cs_BC#V ztA3P)SY^G9S&SZ*LK7#NroagF*|bSF(Ufw03SB>=V>-d>FrsP~_<)Hm3E7!3r<%(| zo@;f#n+GHkHooMf+EP3{VJf|YMsJ%Vi@kY(Nu~J6!;phJuqDwO$Cpe2dbtj(5r#F- z+{HlLs?R^pXCJX8t(*tvV#;KJB}lQ<+}+9^czrh>$yuViRrW8Gig$9d`3 z5BC(!t1PUTpQHj)?`eB!l+Qu}nosLtw{t%gCFSIxH-n`?CZoUOLwmjOgV@A}5XZop-&~-&#Aa~=rRQ2c0PLm7bH)9&J#2HB!vl$?EHD10=8Fw@ zaB{vAkMjhjK^{~&Um?7)jW3KP_Aci|`i%(tG3RaH9#%A3a2Y%VQm}e978FR2bcBzk zG)enA{v|OcV!TaOY&Zil3VF_=evr&Gns`(qN%&er$%SWXJbYe_`BN@7HCEFkM(xVW zs=G+Cf;5XWl}+W^c$KXrMxAXClmF+EwkEl^5NyC9UF_62E=&A_HO2J;qT|xSPz?!i z%)5C)3ulsiP*TyN-ijcREBa|s3uo-}jIbNKV3h{oM>az0Sn^wkK9`e}LdkaPTbtcw zvVGI$pmsqEtz7E~zr-57JJ3gfDVUf1cIw2z8vE8#Nxp+rfAv;zY=C$tyC=nv>kw7# z>o`jCEy?m9Os*~N$|T2(7*(QSmcNL(P%4&gD4BaX0J4lAx9%Qvz0!i2l;6F;+eb*t z`D{uG$!7SGXADUP1iTM!R)t^m$sbhF@2>DFOKF@VBchWW7#5PP)WBqD0J>f}IOlxg zbb}{$k#LEMX_Vu>Dq1tM-KF0NxGuPf2$>!cA>`z_l;x|(pyt~7ahMH|$OXB{!SX?o z8p3~vr(AZ1 zm!LMW-}p`~90X zlK)ty=O6pWGpXYkZTrYGRV&u%@1G_0^2~-~iibTPKM(0ZC*e3cppLaA+Wcbt;~wUp z-TNrHmm`U15{92|)fk~uOH7I=%E9PE5y${gg}Ge4F&E+z2xUKSLFdz1IMMfvztLg@ z%D=!o*ldqUQVA`(Ft8jYZUv=B%)JjVxHnlFN0^PQG&*2aJ`^LNssuybj~gvg_@OJQ zHtcWuG}<~4++#QGT$7VAfo2Rvh=N-sV>UaX5g?dJ4*g=-@8?oeQ$}j%5!M1 ztDfN&neeYVImq47V>VB<+j-KT10()c4_X6({!lX|oI7l2&6NEFsRQ%GFlF#BJ5WBV zPxYmIiX=?9dXLXvK(q7(dok&7PlgXF4`ND%ZqZ$<3I2!5+d%n@k?bIals0n)pfx)j zOxRBqxg+X!;W11;$B)syU!KRy{)>Tv&3e!NQpmr2O6eQyD<1nli9p}*9(h6{s&l=D zxK#of{cHcvnWO^OV7tpy1h?l!hSf^;O};$Gm(oW}W(WMx#RnBs(YC&Aia5Ks{!D}~ zua$=0Mt>*0jEhVhFTI(Ha?V-;t+8{OSL}}Esl{iS3_g3KSM_QM5pH=0IAj|N$m#E@ zX>r!Fmwgpba1QB~dx*fLx&m|Ze(0JZ`->kGJza|E4JG>JPuT0914l1Wz+A$avi#MI z8~XqddY8`ipg$n46Hwq#fmj`Cg!%`-!gs%LT0T3nZC)Vt2s^pJ2O`5n27Xsh7Zq~< z{e98?Hp{!sE5@#sI$ z@mlL3XplF4&^^ytN&D-E-FdAw)$M%LT<%n%mUBh;AIh=kn}uuU;Be8o_o>XFdlL$|Go5X7m1MfX zhnxDO`UY6I%|a>`5B>HQ)TERiH!Dq-_&2omp5f3$=(!RLP9GapULgZ>4wsAjb@+sd zT~HMm1iKM~<{b>(%$h`w_$+Uf67PXReC&)8{i~Dy{;I9;JK-O0P2MUI&nti2p^z5; zIxiV}ml9;krZN+`ty#HYR0_Rvs2Xib0d~0uPVIHd_1YPAT^J&iy~1{+W8zl<+#`nw zCC2v&s5gL(Pa!QC{hkPVG|}hK*Fc6MW`l00gr{+r@4>H$@peIhmZsMR9jpfuBMlM#1b*5detr*Z1Jcm*lP@_k`=opDbK$4z9Jr4kC>(WYW*q9&50_dw`{ylsL=}Ltq6rvOr6+LnES7 zWyQvt&UY#}@e+(SqrHdOT^e4C>-{;8`rY{Y_vnE1pcAVHBzh3|I{)XM^?}C3&!K*(IiH0VKr64CV@a0MgKFTxA~egzrT(+v!f7}l_@)u=lN2m1FK@e zH0~k4(svSUo8bCMsSKPW@-4S>t`zZDqhWc3UqKKLWDtsjAb)?4@Kl@KoJyW{F{ad> zh8l2U#Om@xfJ1@NI2)`$Z^GPjBz8JO3Fn>($Iet#dDfv0N0C^mcSE-D=d#qQ5R%#$ zK8)($SpX#`mY9^MZOIp^?sDX(^##vGlz*HO0O0R8VGF*--O~+#`WEi3)G{v}5 zE_|3kI0jtBZs%1k8_Q)Okj}x1gKij@y`DBKFj(y`0Ip&2XLBfoU2m*Y5n1O}Z^V9R zcAA!qtYAe^6{9@P66zjbQEp|b-D)@5dF+At@S+cdrO%h`9qnh)L>WM?wtQvi4>^a4 z?j3H*Jqs-d8K2~LN9%f8q}gn_+3fNJH)dUU;G0l;5H_T6-rXC&jtD*AoShxCFv(3n z+bAq7Cx_bnq-VVHKn9FF+{2+f%Q<{>$hIi4mK+nTXk^X_X~YCebB)xDf6jhOR8nhI zO(^;sX0dvYN_ENk2?&*;5UZzUdNM8XiGW1y z@4&ogsnpc5fsE3 z_{}VqjtFl3$&eY7e;Q2>QAhpsW%_j_FM&BKqtyOwkAxV1V($Oqlj6=Spz1G!DVZ?b zHC2lu!_LxV%#AQS-yip{7DWe%w8WJWE$e*hsf9(Dm&WrbE0f&aBlr2=)#>NZB}@q# zlrdi_wY#4?q<<7^#c4>vX)-*^CwT}S@}AQ-r?8MoijY1#nj1Gro@p$XQg!?{(bl?N zrW13ARd4dMRlOi|bhvU%DHVVsh+fWUP`S@tXYs;(f?|-Yxd$I6?IihD6|8QX_DlAw zLh>A0LacQC@qD*0+t6XsRNJ&5eRHa^aZMNhVxH2om0>1;@b&|PqEm*#1mDqL z`*62-qqdbT63+5PuKCi{pD1nk0tfjw2(4;Wh*euAVE(4hF3KT3+Op-(ed%HrGQpcy zkWx>T@zL<2RV!_pR8yXN5|ZRruV=Oa%*|c?uR1#^_RL;6iZGw>NHvGr$T5?Fq!%2V zW^P1Ded%2%!V?>8~BC}agBjHKjtQ;?jl4bG*J zSDHNqzOkC-${5L@DJUxREx91ZO+^r)+B~^S3u`$qg%ZD|Q_A?Io|2 zzxxZX^xl50;l-UfJA zDw#h&fyW-@E`GpHz~dAbAHSSnLfvE`S9guV`7sa6|L0Pe<`H+G!fPr|L*VKo>o#jv zHpyx>ftj45C+1}MZ|$Q#?P`ibAOShCH82dJ6JgbCcN^G{B`N{s4|^P=lxmkBVqnfyBMCId4XG70P=XF9KqyYlxSB>c>&!uT&7Tn$@b=+bG#TU zE`?!*8D5lYy8LK+yHW_OpN9z%LYQw*`Ad-dIG`N@IH1GT{Q&pGbEh*JnS{qkP`td7 zTJdvrQhJHeli2_ep>A`hmyatkC71o=dL&({dCShs1hhH+(8@+Td2q1JP-T!`{k}-4 zHu#1yWxH#%ox({k-fU|3sk%_{E5t#?fa=nxOH7r6hg_0~ip-PIq*QyzY^6J45ythS z{+m+x_oVyQ!Dbyv)W~q6!!?SG(ciB+>I`4-u%}djab@o3uOTT^wwl8kV4=C9JC|_) z9_|(pAfRPv?g4)`DvoDj?<7b7fann-iiMpb2Sld^rdTxkQf5i+!T)7NFV%>YdQ!F+ z0QbpdIm`N8F_ZIfAnPZ#N^M-{)sg;Weo^+MMVnuOV&(F)J2haK`3`$6CzfY&XC=T# z85UbAuQq%6v;F+Bvei^d|C~JKC8;jakN}C>`jj5tD!9c1kDYQ;E!^_O5np($P zPq6D@Y$qFsNYK=pO|RPzF}y&1)Z)H%9k-Q_@A8`j!7Y2Vukh+-SIRU63wcss zTf6vUM#shS0_n}xf&hEi&0c>QJEeAI!d#lt*pj2z%bn6(TjOQSY4^r*Fc28aXpl$!P3J5hDpU@ht85?Dc9EP z1Ye~!Rj(IA7%Z(&Xm2gmy6J%u)R;Rp{X=ZFO&8Tag>@>oCxEM!m5qc?va32$3GPt{ z3H68F044mKB3>GAKviR(0>Z3&~xe$)2b4G}icePGLdzCE#eCBYy`x z_G*pX)`G1|hy#Uv<$Z-8Dn_9X08lw>C4E=o5+e3YD@gJ4At1fMQJ=5BBdUpNz+Ci$LR(pPFpu zlS;rT<1=%N5aQUIRe;7FZD+bYpO)h%_{A}YK4=GuZK>Xf+of zd<=M6qZ!80B1z6yLXRw875LXP7NugmHe{X|N5!kV;Bw{@6!uKUMK^!!B< zg+7B8)dw`mVGsM^(~dpO(-eOJ;|)+}%e|id!N*ZIMO^z|*3@zTSHhzFr_ev3 zo&=`!|4pU)|Hp|~Hs4|wE7d;H?*Dy#QqP9>=kjc3a(p#A*0`+t@f zcfPXO;Tatia88xr8V@DNl79Bxnhpa@!>$;_R>ca{bM1kEHj2ypX4Rz6yt@I%6P4k_ zGQl(3PQRI0rZ#^x+4&mZD55(Jm-pVCFunfK2bFL4%?9_hGS4Z(X&nL=mxnvtLlLuh zWyq(&lb6zN(Ic1*H>foe3st9Tuu2bawLa(7>B(SmeRT(WZUy?Vg7~WE-9zPb4=U&c zT^_J)*}U~A$ZB08Y_=$ZT|R_+hqZ0l%%D!lKKSCxYe-LP)veG&Gp)c1*el3tB3x=VK~tQRrQhrac0UR2vkZ zwre4!XW<*Kw_9!u`enY2-4X!o({C{5PhPZKx1gUF2!}@wy9wH-o-N~FuDJf^3dHw* zd~|ud$*YzgBhPxohrhBvMnx6rvCCP_m!bUm#{_mhJOt>aNO9{zh8u!vyf+xY-^2*ALv-6bH{;JuN$mfu>_8%mGPP( z;dGeTU5x%+85igCxRF(7sqh3*V`udFs~p4b6%sz3Jm}#>wWo_GJ961)rMHyIIAFaW zKY1`|J6EztE4OZIA2-n=V~3X}6PiLIdBPfRORhHTv#%8*@J>oM_oME15BeI6Fq?0_ zW7gx!HtBdFvKz=RKUSbGl4)x*fiiJ+Psm`sP`9aEt<}4aHGDSWlR0JCqbzCesYN9IwCGHbXS!ij6Heyj5T7AyYm93rty)`w ziBVnmbC0!ZUM6=j+p6=FqaV_^G-&V&0VFdewT6gVQa%iAsf1&=oB|l3Rzj%;ER#3%)heGDJb#I3Qm!+@Mm)rrj zWsq!y-;7=#ZGAkfO>g|xxS9iBPvi^z0UVKR<_yFXYuveAqf@At`fnC)?kqp0wdQod zs+x>81eZ6*2I>T%L^X<5=4nXpPr=G7i}cb&iJ@w`>bi-EcjNegODMH@OU!#|XKTJJ zb1e0EzPLAM(o6;pK+5f+1J%ln+b;r4-j{-}AYyD_etB&F)f#!_)>CqtF4Aj!;b1}> zA#Aa_+ROdqg&7Ar71i<%aW%=AP=1qBh8kiywZ*50)LlBc+7Ou7ucDiP_Txp;UJDP) z_t>KA*7Aro{WC39{Y*Zga5(`t&ecMbEN>(MXNm5Jzi6Xo9buUDhtE(!cuY)*krAU! zM%>dt1FM_eHx?iMUeN}M!${~S_hCeQD^@>aNia^%Rud)xTfT`^Cmc{gd`@|5!;_?L zR*O4iOZr2FlruttmRjl8S;tjWUzoxcf|R5I?K%kk&dpQoE=on_hHiymzA?JyrRk4h z1c55kqq-lMUSQX|yq>9D(~*G`f835lt#ZWZv!9}E#a#B&xl9p%3VcB7oC)+F+wMu+ zP|DfYMxHJ+$if7^ou@Q=7HZot zly!lb3P_))!t5{nHh$oju7=+Ve{CO2vASZ#P2d{dn`ltRKre~HKzf0HH~lto*?PIb{V-cMEx`>Rk$XgN_vVl z!CvOjITDd1jH$EdEo-?rtl({O(oy|egatuC-1{);BNBu$C9+J0!0jkgvw&cGzfd{G5 z>Gv;rW7VFdH*`w!aR&pZ5_xRu6^*`{IcCZ--xu9gRI|r5iM`u+RaR*8C&d9-2RLMx zk8C$Xw@rh~$YkKErp`^ePm(XG-{V#1_lC%bu_|-B%EgIaD-LF-s4|VT8ww2WX=vy? zALG%+6#%hCUBFuV%rC)i1tXnjQo~<%DSup*v%y| zv7kpEkM4w3sIocO(-C{m2vwc+hEQFWXv6a~VKY|}7TxtRPM~d0@#Af9Fk`kl4mc6| z^iq|k+{o5o%i)t&{53D6Nxlq|pGYM@{{FF|NK!oQKCLEs#wI04T}?+aM^MRwi9T>r zDAuC&!o{ma)~F+PX3q!Bsbg0v1iCc2L{sLx8d=U&iOWV{}JY6D)CiE8Or4voJnHZ-%fvQ$DGj5rRaXg048sMtFtwi z=-eJPM`&%=K(CSSntwD|Tw%uegzqXpmtkGIZ_P9hV`x1<+YhVN>C%1MwCR5i7&I9j zmYyBA+O>heJ}sY10Yg@yPcg4*;yDrTkC#5#tajWTIk#6tJrBZRq+;DsI=u*egNe4t}fCYc-NU)=-nx<^&a;>as-sj=NwF& z=)&1XnB5PENa>!lAWQe`o4)ThRDGUK!DclM0$Wm_jrS^*M-`5%0SjD=O&s7H3rCgN zdu}s7+$scgpq5MYxAS>doZv5L(P^QG$fzK*tHi%Wi&CnJkUXDr;l^w~89cBj#K4wh zy~b5laF5x23zUAYvtOb*Y;4$WHz)IFczran8FX`zJrg2=%Q@W+ZMm$S$~!Wd*$t(D zQ7NSR{PV_} zYYif~Inex`jsVJq=X#v!F9{l3S1Dyy_tR;D&>hpl!QXwN;DI0e>>vPwSO z42CO?6hPM>i z-|Ce2gNJb3j{Mh;3taGtZC=UVq*DezPn|QWNt-GmcESV(!?j$AXj-T~@nIa%u$Lc= zUp8)Ofod7VwjS~JZBU5_@39oRmjGx4?}>b_SVaSSy{htX?NJa%5sVO*@ZR2oDjDrT zc?+TZHvhCld56o07@{Yl7Z=!p-eg=+4-VfPQyPZdrpZh!N4;-A=qG(yX)()3x)FZs zl#y6c%U}R&f#6Qds^cApm@-5Eh);iTnc7Nwr+8oU3>@u(_k$?*q;=>ZLT@+HD{%{VAE?^Ww|=)ej#O6OYzExFsp(d%<+0l(Sg z+CMb(^k+Z7`Sp!qZkhHoLuWfE$r`rl<5?g&EHS->sIc(;ATc^9_Zy5323*+(v^gMM?rhk|J{D`_Iatn6xMxB zBG`>dJjEA_Zsv1yoE=kvx-mA5zWcBY3>w{7}tW!sIe9k#dc?Vyd~851T7p2lG=4@6b8WEo2K&)xSC{#SgZzk9pgPF|!s~GKeo<7?-I|G$L z_h{{%&$ub@mVg2tdbgIduW$S3}p z+w}?`TX4Jw@{xUZ!j}q0LCEAIZ5rI*ero zg1*zX2F4R*W*I0B2xW7BCYtSm%=;Ug)XKn6gA)L56ebG_A5OFgHm(AD1=(=*8-#Gc z0!Tf6FSB3OJ;_Yow5=Vz9*nbQXJnJ~YraO?dco5M$`cR#)fuYYQMSZ9()mVe%!D+` zY{BUu7z(Ue4<#r~j_aT9D1)|ZRgdeNyVGldDoO7jzzNJKbd*H>=37CLJ+TAJZ21Ry?_-NAnpr@+qPfJKG^RK^Z5;x?ybY)yZHpe2-?~V=_Q`=_O4&gy)y%G zqDR+&dkoGr6Fsd^4DI|0g-((QDhSP+2_Ij)q_RWovSp)8f4xsMlZ)0)V6%l~)bI-= z-_ETq-asU*V69-2h&Fl@@se`^7vERSMI*qg89Qn?MKh-wp4O2oUozAO{& ze)H}B?8oQx0SLuHH*x9@`rWT$Ugf1c=JA~#bVQe|d2(8K0JrHw{@G$Ca;%d5TY$Q* zV=I28)7{ZLML2= zBlwfSPhp7mwf-fxZ}M<2-$Unq&<{r4_CyUdBzNiC8X^EkW74k9MBS|a+1zQ{ya21GTGcH;&zKYwX|D9 zl@PJXMpuw5?MCAByQ`@P{dnwsvqfbA6@a&hCh7?`+@Clo8=*^kJ0xtJavAV{zStr6 z+W;phFf64SJ-q`(m#2?>8Y*NuZIffP+Ky`ZAAFs2bfn$4pewd*c5FKpqr;AE+qODZ zM;+Vh*y=bP8x?hIJDGg*n~Rxy@BCG(R=u_Btg~vp=iSeF_C9o@4n$u+kOo^RjQWaW zFY;{|16o%P4R=k&fvQpye7?IkDpXmUmt^{7IItQ7f~T=$mg^2w%?4`M$sb`)Z`uXw zt-_rfgn3K&Tc;XC*+bQX83buCazm3De$y<=M9q8W(SHINp&|3X)^@{ zIHyQlj&NmRHM{EM=li#wRfKaGj1^G*hlYXb7qGRLIhwBe^}nnGw#UQ% z=Zmh}BQKtzWQmv5shuV-1H-y0{fYD^0@FZDrof1XCnP0Ht6wtU4Sn=8QU@z?*Ut$ zn+61FQh*nd{Ax`94pCYjqYAM-Z)x4r_|m1^LB{tcKwZ{w94A5j%d!?_=GoSHh1mX+ zpQcbbg7?JtFeu=DxW}~BvhS-C9S$*8A?iMqZa33b5mcbuDgGw-pK#xBqyTC$GY8=P zil8Rf5wF1AtVe4ZfQ4jumAQK`Tv(A})EEIrij-3ZLBoT-(t}`nNrCIUDmS;-cS=txSdf0jfT?~83g(JFIkF{LuWp& zt2M%o35k}A%NS2m&@r)@`M<8I-BokxS>`EGrC`;{yy2Ks`>ZMvTv12))kW1`3bp)bh~tZ-yw7IgbQa)YyfU z%3IGQH+7f5K8jJi4eZ>$uyKp}f_ReoiQk}HO87kF)7U3g{<@b-E!~xO zF7kOmErZx?j%5v8tt|4I{tvWQ(@7zvfJLZ3h=dyauS99-m5qPsb=Hg1#- z(&S+~4KYp)<<`i-nIR_CZ|0xhncth&b>73KRS6=_4w!bX^GC}ZQ0sJcL$LT=5GI3U z2bQ)E>rHsv|4Jbut7B=ANYJ-4T^Md6yC4$})SCpDOr_~BM#SQzB`&hd7y zb|w0Y?{op0SC@xIz?vB3b|HiTDYh^c&0A^Nrx$Lq;mWmePYA@FS>~^ z-)~8bI1`j$ghSlXno&yxaSaLy$=7;<+W66L6v(v#j1NRGMi^`Z_`#vc@~%&#iZw8M zouNx7F=zLrdGgISqNV{#=u8yKXqUFL#CO?hEV=2isqaRXte$jS*;D)?naF3oIf$aT zIij`tWGq0a_>!&}As|xvZk>&Xaem7RC$tzGUm&hh{sU^`jZ)Bl;qse>cjQe^_F@m0 z^}3zi1@uc-8f!)F@p(b?;3_|EIs;pJSj=n4nMfu*i-u|nPcoDB=Zpy0opZ%PXE zq>b;mzgUTipe%MKN07~CP2^kM`d)i>omjsh(K=;bDt93~R!P}(HgI0#L&9y{EB$Q_ zz~)m-+>WLc^s36Wxm#d$pCf_I;lpd_)(+CEEHS>E+B7*y>Ut~*gTe+!ZT^1xOt%V& z-Fk|}rwY$_%BBgdT@nH0C8g;T2|&`j|LB_-ox2+R#kl9#X@XeqbA z9vJzXl;-BbpV8JVf+%8)p20YkVV2rzgwQ8&_3GtF-Hx#`{0gx2kkARXLjhy*g2F;H zL3^I(dy*)o?ZFP}-udxX{SqS3)3ry|cbzzpzcq~vt0r19r2O7$nK^y$=^xEj7VH(J zgjOps^+6qgJfK43#uISW1Flko2T1(o#>=Jq3xFRW9=am-Qg^Mv+dC+O1coq4C={g% zt|Z5z6;*>`b2Z*o%(;D$;m2yMhaMWhJn>S&4DMjdmcm?6(3uCF__HkU+l6vECQ6V|o2Plmjf_S>!cX zoDyD#;qCNToe`Tqo;F<0xjoI2H&a}u+NCu=JhO%mK#E?azA=-#^UYVOX3zHbPbfly z&KMyzPE-`e0I7L9b%bV7k)7ECG|du1-}PXY+m=)ElfuKi;=}e%!D{Don@(0Egc=Mb zgAXJMf>1IJ4$OR`1r}qB>8*v9nR)qMUuUo!6t|GdG&H8>`^y?3d{*8tY+w>G2KH;0 zDZ0?l9`K$a+o2LQ10&m(p!9$*xY_&~5!iuztvH}V%LoI>yP?nvF5}%{#d`ZX90_@(7(esfg+7Q@*tp zQj#LcU_QpuHtHfKgazZUk31saRLNqtR`bJ(L;&kAI(l_qzQ6c;F z)__X6V(JGC#7iG&14^F!rHZeb(~=H?v6M3LSs$t$Uj#9oN$A?BA8B)-oN_%xUaX{) z5BU+E_tSqB+gafpzq7!NKXVQ(+qH!$EH2{4-XVDROSxbF^9V0Hia{t1;FY=JAtrd4 zy1H{tGa*Sj&pxI2ugON}KVfCQ+(X7wkZmOR9081* z&xWtE90fKDv2~-a+GeXT2GtDj}h#$5D-=dx*7U_i*`}3BDcaqIu6124`0zt(>6T|yEE7y~k zWqgPyHDmE%pMw#UH6^_Q(4@5(o!v*b`g>6?+6$t5tw+xuINi5rfnEUid^w0p+m}%n z_ba;4i$J<6Z}qn1Yq_9g7H6 zz<5|Ve97Wigu%NKqT+>jK=J}$qKSc+)q+y)@w-|4*g$xDK*UbDBbZw^hS^xnXk|aA z_f=spZ-KkFajvDnt%Rr-2LhjbdI7t+M#R&4T7&0@zlHPof}f_q`xgPdY5@Vg{>%Ml zQDJCO8I)|_#w$SCt3iKb+o-1REXl@;Mqs;UIc&5>j@}>yOa5m_{MZllWbzuLyQ0Ly6=at4CrG4Icp0ZR+(rL;p&@zwsDUNe z5A_dS(8`6R(J8dWEipF2Zt~ZcUl%qU)vGLSDrG?@K@}(ME0~o;ugc}%#dlmH6)n*mWWIM zfZT3M)%ENajcMK&&2KX+c1FYu4V5a><;b9a?f38Bj<1hbQ2wkpJK>h@ z)k6nEHAcSn@8mxy&(p8a2_V~MBr8k1e6-YU`4R(6_Y_-n_u_a%Rs`0i`MZK9-#J&z zPT_MpdEYoRI$yvuH5e5YeFQoAVDJa@x3~`&T53VU8S&Qv%v@#*h9vFF*5xxRbM#ek zFTR~Y7A^=A7K|TRcc%`jX#HVb>K4hW>5WF<{2bp+6KY|yZ5!uTy;+Jzfs-3PvG6k5 zlaAhEL}2UBbL!hg1Lh}pMiP_dScD5gNkaF0$5~_b#(4;80Jpmm7N#EAAM+5e-kS81 zo-4|w9>yybL_F3{aQkLP+ecPNWe{c6cW5Smo)%Dh(%-CM=Ei4$u|vQEwnW>vXXE!2 zk)QYRMxoH5R7txi`xgWy8@}}7Vz7b)e*^}|TO`r$j8^%hw((J))w6Po5+?R175N*S z77V@lSClGe=0N8f3o1*tv4KG8#l| zZ0bz8lysyX=iYf=OLZ@BC3VMnAKPXfVX21rVP|)@>1Pb5xwsBnGn|x_fq}MlrR<$_^)0~3ZsW-gx=VGWbR<*ITOPg5T9@p9n7+S= zEza}*8YrmjY#3q`;BMi3t90FeBuRDh49)ojKo))GfwD|426;3%X1LwP*|L9p^T)%|e>I@z z!^L0El9JIH1`9G<-mXlZXiJk#igG<@Q>0`1OoWnJ(~0yT$v9l$s>ZYzM32r^gL4g3 zrRn6fxzqdjL|_TLp~GgUWW>Nkh9&1bCnmtDwM4QD6NPe+=iyQNQ{9AlCD}(~?jQ~; z!NbOa{FR$DDGC@itmSr$*k#Ne57H|dF-SvGk?kir${@++Z_k>4;4na42j;B~g%O`4 zb9i?DZdz36gc>XHxTaI$VuaAw9;F`>+z((+XmumU#@A{0@|j!6D*%)+&869>Xl?zb zwcJJP{md@IRZn|)hySP_4@5Qo@fB2+0#iC9JhE~v(Esv1I4JapS;1jP6bq75!5TzvUiTA~Z}EjA4m)Xo zm!u&T8?(JV%XwB-NkiOk9Z$N*>8b%5JeV#7p({pVKJs--tju!vScE#8l(Y;kAi~G_ zqm3vG6bqIQ<~oNUii`Vn&ZHeX!{C$!nob1|_KrtYuhk0c%h5l57t;p)b%|bCk&-8y zZ+s~4g%`S4MNl&Hjf-a1l&0&ve{qyt{+_wV<;^oowZ&;a%E)Ik+P=2NI9{%(WneLm zyjcSJIog=%5Mg~JXeqW$Z8(_Zam{shklqg-xu&TgXHJyO&d(?__O-O=@};I`J|)sP zJId^6|L@o@<+I1dYmABR6gU+VkYVV<-0P_)lM8pxb3BmTOxb7k7~fI*wR(3D{ekx6 z==5=Y_JopAfWMU1&ThQHyBhVmm2XZk54%I+W9()S@q2OqD6rt~C)d~?z|fLF5Y-96 zKsMk1upEo-{Zs$i+8igkTz4KJl`j8H<}q#~hE5b?QrSn|BgZrav*zqXiW8_8VkKaw z?0I!#J`XVu+0!q-^y8J`Iu3sC+PB#WHFPXRaf)w#*^o4Zna;j$3NClnu{mHx^!}jS1dkQ0 zHwkHqljcu4oT@yXkOowMSyxKje3vmgeipga2$^2|8!-%TD<#hp@!^zBnbCfP1zj$Z zq7hIt#nhyDclV&;?{+x+Pn(DU(MGYzaPHd-D^?RJ!!f9o~)%!LaH2 zzQ(ym%^jYmpdfHM@8+D*0V{YJ1ooQJ2A->Y)yB28>UAOt+^W01@l5zo#8giOhqA)_ zH*$SuYokFpN;VWHYZs4pfjhX*4u0eo6fiHATFrNmOe?L?F!v67EdwXB5;zk^ne5m5 zZSVXB2sh>(PhK8}?|9PbUdGOL$F_Vu-oMan3c3y}N zgv-P72Dc_={5p%C7kPJFitY4x(m%2mCR2~MET)QY^yEI2~45=aGWRVq0oUzj(Cw#ffmX4WfxV!Prq#& zZ&Ade`&8%U{E3G zZi$24iRq?&F*`own4R8R=AM@%kw~!eigsj0)zMtAKf9c;@BZy893joCUIfdg!v&P( zaa)qXPq_Fl5mV9!?yZ9hoa6_ia(&0|L7_tBy()FwW^%AHCDsZAbMxEUI*j}U7F5P= z&hHG%B8Y@HpKsnW3A>2O%dc*}Y!Bm{Cy{c%M_T4dBqck7#(69bL;%Wkg>%63 z%$LQ&A_2bOX{cbPBcJ^SA%gGsuoQPwgrYiH^C3_(1|~VHJ+ z!+&V&v3g&T6~P0>zMQW3L1WWM>(8O=HG+$t#FG)siD)}gog*@2bkw^!AeT8yt!X?{ z^y>qZ`WE|Y(*3N9q@d>RjjV@DS;^YCyIueTO5#OJDZ1sNOY&O>QiURtv z6ZH%vGJC=03#RkGSsKX~1?ty^0DxbZyZAg|)lX?cGLlPoqs?^cu5P&Nj$ZE4yIdHb zx8eridt)Ka$&`-rmf!*d3s`!7qmTyVhv+i{P@^Qk$Vjhos%Sn0TyWG#LaMS79T+g$ zct^U%1+c&B`yaFYVX0dZ9!^p6S&E2&Z>5;8&+4^+h%kJ&$MDT14)gF)5B7g>Ma-$k zz($4q{8K<|P?Q+H_EkR`U9~u_W+5LQ=eZ2$8D}wE=zr#rb0-c}gbaXC1r$C1VGaqf zyuWYA@+_-JC&9AM;E|j`W!4sEd5GKJ_vb!f7k%l{r>(Kyw1h0FEw5w&Xz{t5^GxsSp;*0D9)f4B#Y^(}u6Ox7Cy z8&k=OvUTt9tTa3cGX#rO zW?Ho-*18#d0u&R5V3LRg6`6@`sMZNJ4VmZ78851M`yd%ayM!1hz0yudz@+ur4voD3 zG~ZA2sgiJOrzkuS$^x0>k58B!Yo94?yHHe|0S9aiHk1^W;c5q}OEcy6q`O4ORz=D- zDc}n&T>Enf3)SbiW|CQs_quWCThL;_r!B7)-o}dOc#@Gmu_U#^L2y4Y(sNHpkYIbh zPvP~Wl!dFCMCWo3m~BF&JjSr09i8D^9(8*v^N`Mv#QbnbUb!Y#${n~8dgAdTqCNr1 zCpfZ{!(Bmn3%?abg0cBJB553qz3`$q6#t^Q+Y57-FNLg7qa7Q9Z6Ge;C4xlGsVq_q zDrBMkXILhe)|+6s^Lzm7PgaIr0rsO(lm9{|Ya)JrVo4>D%wWT7OV#W+Pk|T1-EKXq z@pY4-)PKOC)K00vA5-@BJl+{?9NM*C%8J?e>E~K7EMPh!{~Hvk{gOQ;Xt{)U*zuN9 ziHionXGbYnB^+EBfwI#Z1i|CD1-SQLfdIABdAgh__|DD(B7WW}7S6ac82`JYWpp9)4ExYWdD3xqq6j}g2NFT@7bY^?D?=6U0gsIuihz41*kv87M zw0P-4B?&}e8R=s;6fqb(TdQEkt*`kK_CA}V6=$nYPao4$(J?fB^xsLGSpmwBiTjA! zuyb-&1NpiT#?{Mymqm3qYQTx=rG{{uC(0e%dyreHkOk-w5=?D5v42euAoD|%^LbQA4-d?->sBZcMc6gx7`ymgUf2*%(v|(j zbGgJo|Czzu=la$*i|Jc@O+ni59iN`l7gMflFk2K-s4!CmLlu?R(V!3{yi=`&;Pv$Z zscfHahSyc$LqghxMBF@7xnw;wLO?-sPWDyJHGavI@K$C7+RZ}}j|EKEQoi*P=TyAL z#ZR7I%8QZ-{zY(Uc^;vaB!OcyIdbuOQSCi>rARYW{4r|Hgd1 zC}VS>P?!nfM#pI5k7?7DD|+vJ|1diX(#+XTOhj~@QwB~qU&-Y(C+zRKEcY`87<|J! zw7o5Ahz+M(($`H%Y4OKNbuF&dUO&aOy>-oxmDlq(uBNCkRWowP%+A_~nS2Ji|9r*Z ze!Ipps6G?*8(|qLN^HzJC}1)>Bz))NF5YOa>$puE+29Svay5JE*XU>s_;}9@fO+p8 z>10B}&Ux;H(&Om1ee1J62lb>NKugSk@`Q!uu|#%_wMTF|XH= z#Y?hDDpD6npKg^2`J9N5jpSJ!7o9toegk@u-KgH8?sD(@R74b545oq?so~EywWBt1 z?!;GMSc_7p`}wC)Dr{&+nixayH-!6-FTzPRVXI z6|7|oAJ(bCe=P(rP^wso2ddft_TOB916|rg7;GGUgB!DYyuNS49 zZ9~zk7Is_d_3~{Gf6s7)9DwE9&e)rpJ5(t3M%r32oA|>z$R+{pS`%`zk;P6K z9zYfLum`tN$UgXQo8U~|;+&_C1uE$M2&Pkcos~EgE&HIRZ^B}>-q4Vs5w8(;#m?fh z4-xX^h;TwC2&JDHESRVZ3+p($!QNcdD&VR?AmQv<^E^;fg&5a0d0qLP;Z}=vs&HWw9|L$Kf>!xbHzvJGW zD2fTxQfzA@tL{CMd0Xyf@~3-UyjZUIkTGGpU)4HGEq%Pj!MS~ODbthOUH?P+Dn8*S z_=rr@@YS*=CLefLKKU$h2mhG4E`I=FeSKH}GtfegR=|=Ds^shF$h;{juLMLc{szl^ zw3VgWmK&zt*X ze#4MN)Xa?q`*7!lH?m~IgQ=D4K5?}hIQq`5$UKO?k@+t%B%W@CTk0R^T7=$lLKOKY zlRM3v_w(&}rfmyl`RxX0!uQBX+Ck$_lVd}8#a`yyQHKpFnL$t@<&o3p>XdxG6zeD5 z?(r-B|BzKG2)KU;Ym%%SH2OcUlqt&?0&(I;BVDcl*0uXxPX(Twi>oO`=dYii&L&Sj z6Gc{SJm%FiXLS-7@7%|HqnX_m?`v}~kX)PeV|i_`lct^Aiue!E+T}VZMS1Zv)<0Hs z%c?YFvJU~PV`AV6<`&MO{5C!Q&tSt|_O`Mc?xG&!yJeQFJKIh?VQ;xAZ*b`+EFQ8Z z&DRBmH?1*$Lig;?oo<1@ZF@pA2P_?J1Ti9<(+;C;QYB0&U!!Mg|5QFY-@xh4wGOOF zh*W@xK*s?crn6nLn;pmmJ1S0h)7G{E`V(Mt?A=n_9v+b5ZvCf)AB&_XC<)GBE}&fXHhn-~5Tp0Rgl`E3E9gtH2eV9hBvSuwInYRO1M(-C1Ca!+tlfMnQmwg{?j1Bg zoY;U4C*T)bKMy;2h!=Z;%>Fx-#1{HTL;BSZV$nmTlR`~RK>9J-&ajFR?^uw(GyhSV@4O~}&^z_8gAW!c4dOu~B9J6&jiJu6bDLiAB5yn*omflrX18p6;i9Oa zF71`;Md!wlCxi^0Cf&LdHU#f&9MHTq_fe(Yg$?P0GplGE&WuK;U<~LROObzUbs(5W zz6xrHMdtHCfo#bLDoiCj{kaMyU!fKl-@xdq4UsjzAlg!&YixWG4(r|!1e%1v`iVI7 zDmLhAn(73J5YY^jVD>q@b$6u4hXS&+{&c>FLG&rX?jLI((60@foP_AR^D%sl!e|*&k9qwQz}){Bsd9BS zqF5)C61c}aaj}Hn)c>}9wh!o91X%POA9C0;POiUm@_!{1sxA#d1^?+>Yur$d>-H`^ z+eiJ244>0FR5CV4^v`viQn?`7Or0{wL2*H(&WOZZXcIT(ZQZbPu5VEgae&K|+)P9V z*EVNhHnXD$s-9#axbMO2)%}J_l4)ltPAaV(Ys<<30_S7Z^F6s*+V@lloJIx()&T

NlX$1zP_xXC=$>T=YhObcdg^hY~tYLt!*& zXgE`lnpUMYO_!d|YZFUiZkT|u$;2E<>SMKFKv^Ysm=iWV zmZJ+1l$`)LE;@RDLKG3tLF<#cpqP@~t|*EJ48DND&ME_&kDkFZ58e?DX1^f`j5Q=| z6A6r+G_}>gI5`bRv+K=$Nu`Jcn37%z^HRy|7#Dp4XefD4O!PD8WXZ)v@#rmgDYsKT zeBSi(%-~?EHJIq$n0bS-6{{B<)%AW@(&Is|3ya^9Z$UMG7QoL?%LQ& zm~2zrbQEj;Za-6f{(KCvy4*Zs&GX_P?H&QE0c5sX z56PXoF-KpQX8@vyhsQYm|3F>NxPANNCcXgI^%?sO)BSoBn{O7I*}~>Hk58-IwieUB z#>O`<)6yAV?fzJwciWm@FWHrGyZ%kO4JcW9LEJAPOj7l<+oi8E+#T32#JOq74shK2 zd!VU*F?5f>G_8$6D%gJBjUuzS?n9bLFp%$WExKGknDy8REx|ft+MJW|bSbVr6Fj}R z6&jN9B>eLlzrh$1U3Q1u-4Q+1(Xi`kEyI*-)V8E}FCmpj!Ok!*Fe<0o;@a`2=xl$? z$q`4U$&-^EQCOYP21-0jW>L~5Q3sw{C{)OK|i|jHg>e%v>R;+VX>FG{);Jb=v z2UUwqsv-k*9{1C#q^Q%2&)@6K*&ZG-xmaLD%}hV;c-5O%vX3034Q|k5>6Dfi_a6n9 z%4y2ipX}Z6ATmLUD}yexVTmne?8K5TgLoQh4mM+K7b5=h z1%VRLw&&10hy?58Q_Ko-(OI5px|!AK%TN04u(~$0pTV4A_{H!Cu^w9jO`8vil&A`n z-P)sAG~z2CCFXlmyYcOgm^9;%P5ggH7L8enBmc6VZAKAUg|cw;*syTY~w^87llUwt62yzkb z#tzV6HwNk7Hqk_3c{sDflCgm@ys>k%R9OO^n0Szl3w(JhP!IsDTWCh&MS@)X5HS37 z$LCV+nfXmPWa92iW&^0&D)}IAazVzf>33}HkJYm6Lhv7|x-uhl+g$7v?!!!!w1Lgu z9-XQSV4^$)-WN6BX92Q1_NP(wr~X~|&|*eYxkSo^3XqL}AM-ZSg@IzRtKUC0sU#=P z!Bzb{scZ|Kfv@tqTB}HV5Cl7e59(Xu>L6LoP5-d@AM%vPk}D!Wk^Vh#8j1a@ypsWV zJG@4pVggZ)z`cI`Q^8!F{#OTzETsl}2}=MCTw3*d9CQ2RN3vYN_SAq@>%9u|<1(%x z3$9_^l}IjU28+RGaoqJ)_$`U+#jZ506i4nmjB!E9Rx&R_z55hf=cdh<)QdMfpAya> zF=ea&kNi{!Z_Non{XA?a%tKn0!Am4UNyN`br$jRk6#zNkqNvJHhZ^q%8i|w8IpAO)ZK(AL8~7<5c&mo(Snbw zv?KqsV~4S!o(18{F_Lc`S@CyU*Xa`|fM`8Uo+GVsCMVsmPVRB1n*iB&N8Qq?TGg-m zdI;IXe2FctCktd-8+KsstqX&H%X3YxY6A@WIsy!z#v+$rhdaJ2RXOzZrTO*wi;ZWf`@lOyp4B}w&^pO(A)KS-Pe9T*K& zdQ@vdqb^URN(N-3+O*3&y=T4-w}9TvJMl&E57SI5)NdWoy8lE#_kFX#A30g>FvLSn z2TRd$n}=oiqn<3?lZ1FMRBN<26+k9r&O^>2{v4E|Nn$}eblET}!--m7&Aj_!h2LU+6!!J+|Ja`o93Pv(kq@XaCBt8vHr7CG(Z(rdJX)cN5v{UE;#$UF;W}|5=J$vYBbpo zQJJ2YLdpR%`d+mFeqsN)kXUY!Xd+uL=WV-GZ6>kDI^!E7G-}Xo+IvZ@K8~u+G7&=&r zgGc9_Fr>Hsz09Al2?ezD}IiIN$FI8`Q?ztDE&t54rWOlLEG# zG`Tj?AMy|D_$&~YWti{>SqR?+eKB#4qVcmqgGtOVy_;jR3{)1761e%gypa?UyNSER zk&6TSCZi)XmZV#YPT1;lCn4b?HN8#Itx5S|K0r$RW-s_YXfRkDj@*0xMfvk+Dx;if zvo939!^C^Or$)cZw&v`>nqN7H1&?9+)KcP#R1tJTVx}#?LD>f;;}w>-wz!BWdR$3K zZ26qwg$j8PzhHqpg-4}5yGvFO(*pejTqQQrvN(+isVx$x)7t-kHF#YlxoT{o9Oa`}rb6DfA5Z3uLCPR$lJ?mMBpb6zhQ(YfEF6coo60BUOy!L$^@0VJCSBp*z#|p zem7h&4Ug3?_(wMTOuMQ>L>ki#=was9gQzaeDY)idT+PP|5ytTt+8umK2b#ko zUKA%@nBIaFs(>e+dMEa~XI#}7CBw-Qu1O2lJM32-6OP4h?J=`YCgBYvK3o!ZN!oD| z_^hK5f(Vb2_UR`fW4nRhF*b23nFf+$r6CB)e4fNvvb}Sq`MU&%SlY72T-aDFdh>IW zHd{Duc{xk8^f-q03oen`XVJ{eB>)1BvtQ~$?EDa><@a!G^S0~n%+imwK~I4r{;f3* zsLl7aJx|AnDlfaafxSt^Ul$}rDA}FnBzGU++oHD3)A#DrlY~vXJl-gW3O*_8G z6kpT?iOb2!(PIBooAdr}wK;H4@G+lSAHvgdj%$zosn~2+vLEF?Bu0jg74N@Pj2PQeY|2wL|^#KAIt)&XfIc~BCE{$G4%r?kP8ob{X(IropRrIpPY9&W6WP-h13y+n_K^H~BTAU0z=qQR4{P6}0Py!PWjd2R}g%RL9y z=UM*M@p^IkP)_i>go7KBH!iBy2|ke*Ps zr-382@}2hemDb?0pS^M^q4mT-$Dlq1co-_J?s8Ac>Rye_}o@Fo>g?u$qwv;;M0!U%wLUD29e3P5T|{fJpWkjz)OZoyr(!t|e_ z^NmbRZkTR5gCwjGfEKpj43T%~5PRDtZS?XZs(}DtX5~D9uf~BQ*_Z<&u{OIRN@xuV zEIMYEe#)oK|j93e{PwB?(vGa*_ z8KY|V{6d%E_VE1lQP zoWS^Y+k3U+x;EZa^-B6#IO-I95q?tkUuc1{2~R0Zs}yv@7t9`0-*qurViDpFK$AuH znDC553SPG?T$lrOG0<~mj|l&|F4d`V9?t5sCAKfh1_3QTex9MZujd~HptM)t+E6W;fu44EQKg=Xo8-x zC{%Bi-6!7GFDW0W#$iF|m4W{YQOq`aU=DDS-d6Jn%NQlT=%Kl3{B8g1;8OWQA!9z| z{B)>Lb#x(0P@Q@YN_jk;2;oRn{f2URVpNU0Z6=isiZrWq-zwXq){OZ>AxP=bsMDsy z%K)5`HF>y^{5tpp%GQRZZlm8OjETZe%VPED_-d}Te-$ZAquWxZ>&!*>r~fWDhDU4_ z&~HR%-HtrtKZ$cwM*ktsc@1|Zjq9oe4VL&0+;eHGXSjx%C+%Y-Ye`*g$(r7ZwOWppRv zn1WI9+acA>s;%>H-R=6OnCU37sHzDj46{i?kpx3Tj}D6R1M^G@tpv=?gOaQACTFBc z6k)8PV2#Gxa|sJGOoyJqZqZ{~7O72~&itE$*Mc<`&9kSvsxp=4P6j+0IeDW6&RAB zrrw`Rwy&->46c7wl?!n4#=xl{Epxgyu}nzh0>}IbKz{uqEd4`vgNPdJtAGV(eX(A) z%qx2~C00ol$!}l>zVFA#8B9`!)m6{Ut~$uo>JknmQ?sl}p1Gl_nZe-k-5BJb1T7 z?X5Vd6|4(KlR`u$HQ-C9qbQnUF~Zs*De$Ccd=%35^u_KCH@RWw(SMjy$)6*?wyC9b~>L0_=QeZ4|W}BUpRN8yy z5a!qFWGiMk6Q>4)A1=vy_Q00Gh?mqTZT=1{7hUW7{A|-5)U)QMv1AFWQ089fBmc?kE&FWWaH#K|*oN2BmC3NUAe8h3~AiK$P)H5-e z@$~Fm%f|FVV{t)CmpV-pxhq(FG_xW$dv^&{^yMfD0!m?;1+nP@yPK9hG zzuS^ihZ%jty@Nnw>M7|P7N0Rnku%&kD^WNwN4>onr2|isZaYVNxK2-mO%xJR$=PrWDfc~L+F#0B;n1z2V)ozWP&02C!*C5SNLRL6 z*Ay@Crd)IiUFkhG+-Nr4e^dBg@Rn*&q9?HuyED_qp61||IRc{k&N^r4_-aV>N0Vaf zf7~5oEjs*jOy{Ch3ZMg?4f4 zv31!(&vPv$;yNF2WZ{1CntfsMAmY0cegCl{8!pF?bRL{^0Xam~*=7Yp=3;R(x>UK+ zV9sQ+SZny=@$zVZL$3}-(>#Ci0WKJfP=rSZeH@OR>Rx8Zfv*I}-*>1*!W%!GQR)*#1T5`-E>JGm+6s z=&>c<0D?)+e&o;;>wRI)sZWEw|F_1W$lf|C$Z*bld46W};9S%5odLw`nM3C6!m*Vp zsjJy@ci#YC0PPv0(-VQ!Gya^*>pqn>S3s@upG0W*rL8JwYQ2E@cc3L~UL)R8MJ#VFy^)szm=?Mh0>05^t zw{uJcpY}XWrh4-``|H!=85&g>^0dDU0ngoh*%|B>Y%a%;;qio0J*&k87^p{)rjHLh zO%giaj+K0=ifjt5p_9k=!F>7C?5aB9 zg$;Ccdy(a$(iFiF*JSj$^*DLNhtbVyq|uDz_ZA3vO0yoaW$YHB6Y&2vgytuNlD|CX z{nsXjm?JRgtitJ~J(A!wo$m*p&o4)trL;*w{ye5WR}^q& zb0WMsYFro*9gI&R(3w4PQf>JN%gFoICb1w&^ah75^$wc~bu~d_utuPgN4TYl1y@fT z7~5VTLL_Wds|>jcV5Jh!fproS?^ZWh#*}t%oS^~d=zqB?-Vx0ojVr#DN}>{-;fK8d zIBYxK=n}3?;aD&fWDS4##D%h4VAU?n!m&gVf5>B0)J3H~o!L`4;fFRjn9b27r*s*QfwrzE+ ziaK`ENjkP|+qP}n)~PwynrE%G_xJ4|XN)~g{d{Y@^%kGHFFe;35lxLkk>FNcmFh1q zA27ioTz9mj;#6`;QwJlsxkY2&N7xsMTN%a)BsH~L!z&HP39ny4dc^#v+;|B-T&n}( z83dtX9QoVU*9iEQ6^)42-rfQW+hxi7_r(9qUBHyL!XHXXcFw|RsnKn3o1L#Y|9o0~bNTtljc1G; z2P+B%mhA#n4DlR^Y6Bqrbjl-~X^R?2IU~|XW*ZjW@h%b|W{tjGiV?~NP(c+{;$d)? z^KKnlzYj7$I-$XP=hjpYphQXFAy~Wr*qQ!L)j!cI*53gS+ZO_X(4+1ewv_fu(<=pC8&=JF+j6+vgdy-Cd<3ddYUg($G%PG&!R=2;;8xE(thA}ij zKni&W{ua?)hfe?8K6d}WH5q~J{gfx^+c zfx&|f4y}frK4l)+!;$5C^fAL|e-=$5-@Nno(%8Sn$`Vl6E@19Vx_zc6R)^o1GnD#v zj@u}Lqxba3Tz6e)>6k^($PS6unKN`cQ|vvt$y5Sm^#B3YMrbWCa)TV_9Xo6T)dz{p zmgcy1mS1ohc5{leXR(_+A_^quxa+ZhVGmSIJ2_e}g&+8tV-u-%%&5%W)S&~)71*EI zkavN}ibf>!VhkfV;zfcZCb=nx*R$m*?uNB0A^&n8b& z%~IB`feSh*LsS>qlJj`B36CRq)mzVRHz`h>2B&z`njLMb+6sa4vk##nyB=XdzO+4} ze?5pC@>*WwlYX?ewreGt3+fQZV{Ounuo3c>F&bxk`c=`gY{ZjOqqs^S(t_LdELC*a zfXaG6q%2v4YzJZ4EEI#;Z9X5$H%Av4WO$vn{#@9J1G2jk3&Y1kB9YgWj2_uaRMA8J z>8I;qLucvky%FQ;`*x6=>dbcflr`bV3A)hB$+eTXvYno{h8}sl<(qMQo$|%LjZ{e0 z*~f73Uaim{WV!U5D(HyO+T;kPXl+Adgdd9*JHw)EiH?x07($1aAGtn5%WQgZ<~mYt zTt|Vbwq)FXsi9<~-bBC}RqN56A>fpVM({K9yz^f6p;)PK!~Z%)GU1Uc7ZiVc)R-)& zOhR7*(P(&8JoYa7mj51@U`wzn|GYj(cV2^1n}y$gh)d_mJGYd~u?kRi$-amX-w#GU zcXu?~rU-v2h+D2QrtgSPzIv3S1{%p?l`SrI`9U3&j5r)$m;-qYHR_M&3^(pQfmo%35G*t#Bt-J>M4|M5 z4na466^+gFfo*n@Yf)-k`K|22DE1$zK@M@g|6w=V|Hp1Na?a}=)yF4oisR96u`{H> zGcLv_q4UiA6L`&IUiq64VHdQ^y2sw(LikxCCaP@le&oG;y}iBrI3|bV3PhaoVkMoyRR#TWlB}FILxqKA3YEr5%Y-M1p1QGR?y}V zXPwe;C2PnC$je3-TyIq)vMIinz!dfQuq7CL-tLZP7EWm*l8e5boL)LpkQ{d?+{^`W zgayW#GT1JZdSWHx_aFAZ_2ucpU%4_G)H!#P?GXg|ph^uh!88kZtOvdbTr6SVVV?0o zTks?;BM*Z&s7Qpq1(>x4Z13v#>F+{*6Hy3HYJmVIO zCHG=8`4As$DW4ppqj`B1;C4KZke@0PurX(uN7SXD`jcE}i8d7ZM#sSe+Tm$I;E%3v z8q>yF+WUO?zWquL$KKpOR_$(D!K{8Pk$6SMM|IEVhd0JGTMpMLJ~s*O9!S@m^qk!H z;7B8qK!gM9xL=*B(BWFCw;C0i$C)_|aFF8J%e<*Uryo4G&?xZpGkj z^i3`CuFv?Ec=R)=zuw`c-8AVf!{`>@AJe_BB2~0Af#s^Mv74lbL(Z!z{g2PO)EAOs z!#_OBiadjU26DF_4c2gYEJYZWQUGi2Wzt7QVG_+dHd@p~3x8J?wwqX^(B|r(!_QDUun>#rZ3W?M z{m%0VT2l(BTnYWTwD>kx2@`~UytK&FvmeWfmS>y7zt~Y)baP|fk*O7Ux_Wps^Jnn; zv3r1ukmtT4`?0Um1FLQ1p|v%wV0Hev7Iw&*<1ePrYih5t4m9jjbH-bGHPqZ??CKaB zuFuh}FEl6f<<`9V5ck~Sn{R)1mtiv24;|S_;`{bWwK?8cX<(y-R~`>;i3-`BPlzE8 zod&KNd*=?Tb-RzM?DXFuXp1Qm*~*MMHL@xfQ*{Y6?Y{SoP+9chu1mPN5vOig`o?fi zSTBpVX^vHwO;ZD`kj=(PH9Kk(VW-JLBR_&ZbYZ@8eXF_q4bJl6aZuS5pmJR>`I#dj zD^1Gr241p0>kiaUeio8cnb@{8*vPzI@R*;dgk8uJU%kJEH_z+}B}`%pznYdGu^158 zI*)EY?svvec2bKYX4OEVv;^IqAqQkgd*fqE%GZ8Ke;hy^``~^fk4O=JirAQQsvjJ0 zgi$$#Gqh+!7bab_g&GPoeC^N<7)Z~Uj3yq_1z}#|T#9F46OzmQc!!#YzIk}-v4u|5 z=mcOiW12H&;j`5LcD9Dj)qL66I+Ea@*Vk-AmZ$%5rY?(jAe_O^z$2YG2s#DA8HcQ6aUu>}aAKP0e zlj)bA7_Du-B?N>Mj~v4vgD5`~!}rHb;Gh4<>BixGvZgqF_~F>&K)LR- z0YRC;U0x-MQxY-DLHcn2cWhbV@X&G@r(1^5C3i%O_C&>Vet=0Lr3C{+UU3$zyC3v! zFrz*{9ab|2xt|UXR?rE5drwQ?rUNV2XC}?}V`G>p_U5fTkQlEpqUmSI+9aAld|B*~ zEo7T&lJN1`4Ff4wc4utaPkwmy-4Nc)VEHo(o*NcXM69kZmw9q_55>Le{}b@zbTW`B zvQIrr~nV9jqHi)2>q3tNz0o;n_|H z!WkdHvTJ^H?3dVx{owL*4zD&v83b$7w~dz)jp(~|>KhWTF34A&7ib2D`5@x=-0vxT zqKK8Xo(w;^VZ9N|MicBB@Z??{l@)izKB0x6xF2Y}AY{#sTWGA;YclpTX^7uy(iVT? zNt+-L3zNFd!S{1Kq7+8s9oAgsT4YjqHkzXekerP#Sz=M~;>!ffi!sVtlX=eaqQHX$ z)Srmfeu2;GcI`rGcxR3jKvWx4arB>aqNV2eqrx-FHawOKcB{ zAndrNqUHI{M~If5qi@X|gu%J8&TZwBq0yAamT4W4i6S?55GkBC+|85+eZD&1Es~vN zWN~%enq*^T%Ge|Wg%^aQs8l=UF<&531-1+-k7M!JZOZD&o)%TlEkA=Q-j>}D=XA^WDZE73(GRAVZ7 z<2Fjke8I1p$PRTqawisb?AMNkE*3~HKe@`iT z+<4!Rs;%Mu9RvAd7ANQUR}2bq@md&8%u$2SLD4;+98+<|~eSBLsM*M|^h){Yf4xx*g-PlvKAV3+SmPhEQZ7b~E$0|9wmltS3z)2xJi?MM;H>4*IZkx2 zb#`u=M%wR|GdJ;i5}o)LLYCZ_E-t;L03}gR483fd67KW+%T=J2>;~|JAy0R$Ax0FI zgZ7boZ+4c@=Ak1g(PI0D9ibc=5ah0xcRjxR10t%-w}Da8xpRia^bO+{sZ_~=y$v5P zKMkT%E;epLm^3GGm2atlDmd`d}OoFGqBn`_z_{nKV}l@*zta(LnnYz}aN`ILznG*osKbQVl zuzof#!Wo>!k&7Ulm=#TGsZYk`h}7rCiBWVk=_%S|7yJkrda-EzjeZ%|m5Lf-NoCMGi?$Eb*`K~!taPm9rf;ZmFWigUK@mXGPV8sdoq zlYvt$_wle0#%I+cyJm^`5q%?-E1lw#C+xdCU74}qWWrqeL2zp>bo(^OX3KhV)f?Kf z&obxZ;;pDCXIePbb4Tl@5@CcsF+qK>D;@wNX za)Ib_D|AiS@IGsv?i@4D>82q33KxhwQAkfqSL3HMyB*l5{nFyIk2j8%x$A)qV}Gf6 z)4R+UCI*iFbTir*Ti0yw-&_w6JU~1vsEKImB7CE_5|Ugbk$r>)-ai$RJb2T&iQywl z@}%W4ZZf&{;bg8I$4`fG1_!WS^Rr-i0&B=G60ug2PRF=uv|MY9uvP%WC&Ru2U~7Y7 zP3`X6a%gO5q{6&fhc$29$hGZR?dT2vvVCW*vs#RDIbXSvXAxu8lo|baXjS# zGHr?q+&yO}&M~?mLU$t`A*uWnJ~wAtZKkQ#GRDoH&>fj&xnZ2PIqs?ia3u7gYBl2y zI38dnk6(4>eaM;+t|0PcUsF-OKoR!tzkjykIAWj@EUzmSDRNSNEN%59IN3JY~N5 z`u=SEknJ8I3gK4+JMyz*QVer+$gzGdGc{}|HyHKRW+o-$=1FVLaLO1mL3QWu_0Q#l zr`f>?E4uCZ7?_qEDMmwE{Nl&M7{cch;C!1wFv0uBe-=BwxbBNOo$8R;Zk*~Gum{6l z=1=?4CsuPIlwLjRdR66fu^u`c+e~$(S->cX4Y~Lxvu}l$n!^76vL|07%wpr@em+Gs z)66YYY0%S1zTFI1;hD__*5vY%c7UPOY9lLB^WhgWlwFONB(Koal2C@UP6GbL-`Axs zRUVrXv}Bb=0dmJb;de$P3p%kSAQ0+OTH;16B#3p|N1nmgtJNlJpT^}lGRn7>y?BF_ z6eXlPM&f&IXBAP$a~i+dFIea7b9po)dBrXr*&bcy|E@M7kV4czlHj9v+z?=_uXlH! zb)QJ*9&ElhDy|sbK2p=GropHve@&{CJM=XY=~Mahi{Q_Nm@V{_>99Vbhqy(NAea;))PXC1oJ z;cbpW7FVl335h1zguSq4TK@d`Uc2c}-*TnLZjM4TR!0iWV)*7srL(TNl=HtvR&Tgo zQth>q1xu&nnl~)=pR*`SHEcSo4Fz70c+B^dBCg~pPap67+Q-)fqh@e9UbU)sDOJB4 zTlTMBZ#Ko-D+_**6g!RJi63Fj)QTYi7@xhY$pyw=n4VLK@)8NZ{Y$}9(I=M;e{G`T z6tsWN*KDw{O9f27Z)4+&hJy8GV)#_k?Co<*z%tb@2rWpix_^&@lA_N{^$Na>LIYcS zfem}?&Tj#=s`8Z?hi@uOW{CJ?O20a;ckhY~K$$URUKqWFXnke8G+C>J1V}iln_8;v zOeb|`l&c2lwiyuN!wiM|EnXRjh9Y?e^LtoTBa+|(&nJZ=vyG1Tvjxey;$zF`R9p0th3|bcZd4)C6`SN0g*1m8@u3jWrsL4lepPwD{{Rkmr!@u> z=u7hH5TY`^D#I7_W5?{lAhA`%X%Mg_+<393>{K)=YNIL=jFGY1F{fJb!FMkX1PmMZ z81If&)oZAu(8iJ%vgJX_FBh_+iE;YW`G-I_K5fnD_Z2 zH6Nz(C5-0&wUa-33)H9~%(o?5GoTm@bJr-PuaAxc;{jO44qF_O}%hO1P68QYoJLPb(zca|4PwI4up^( zA@TmVptGrdkx%aUA)}G`(5Vp3AK4!i>JGk|jG$29=H4pPIjm}wN!~P|RhV>GNZ4TT#O&)SJ&z*WQk6&&{_9|tIW3vTI9@siIK@L&a=JUz?P4r_eec{#(~r!(t!j68pZf|(=0!B&_os-j>EbQ%{pk^sidSJVN-d;~HM zwnunX-6m&AgeG>7=Zge!0| zu*YLg_2!rbM%UR)NNbt$%}+wHBMkL1t&zi#UUs(#1+xALcWJmH8S?ZH;JbQ)%s)A} zgJpexx~Z0nyqoGIp?JfqOe3RdgVV6qx!)*ov-n|m@`=%0e(`IW*md$nR*l^JLW%&} z{iCAhm@o3$>AGii9s2QriQ~r!z2Oe(lZ6WHJ9~sYn_64Dw*8&=A8`A6%x8ces1qf$ z)xh-BEI3eUK09A4;xT0@24(gJbGI>;iP*u?+O&?$42Rsfh+1ly%lh2GEc<2jsFr;7 z8*C5npf?J{?L{qnzpmZ&nLq&xbk#YlK(`y~mSG(f6za~U@c2$>>HZ0kj?Wlz88Ug1 z2TG02mOI_r4(@C$%|D+yUfk^Y3;yGyMBhJN08db_;+cCTSuHdiExy4jQBJf9(m3*CNbbJ4kQ4f& z_hL`iD6s*gSEakbu~)h{=N#m_9R6sWuijj2D<0slZJQ~b-4~QA?XX<`U}W}*z|%E* zHe7T2_J%W&K(lSllksqfmOBvrff|J5cBbQAxm)1XQa+ zq_2vw!yGS2Wbt_>Ot!^ld6k}iPLumdE~U<&N#E1c&E?hNaA8SRczCr$>y5d7TKqx) zZzSV2xNkG4E53kPq>cMiJlJmOwQ^@J6(RxBA2@N_aCLgN?NqcMO28Far|nVlv|`j? zd4*dQV8bV4G}SwAKfm^aWj)NwnJz+OYu1%vbz#idE)|Izjw7$YH2bkcCR`t~20V*> z_PUqmjn@_}z1OpfL67J@$WKdL$+Bg=4H^skX60qvli@<)rb?yu%w zWPbGWzK0!hE%dDyZ5`}~%9L7^J$W+Y3gQm4SEpaeyoxh_MOrAq9=~DBSveA+PM?a` z#N%X)iyf+Y>>Ef6Eedfg`69CLtoJFuJIMr_czX~Rd9Ab)y3!UC!o=Yg#GLKb%GpGo z)x_O>mR~uYTfxSvs>bal#qr@4oGEj?m|6e?C<1#=Q21qOQnu@rZ5y4~>8}tx zuI3?)-}t-pS3P@tQp9_uq}-Zq)i`-xm{B`dgr%REd`XV=WRQ0rzF%rx8fS7kpR`lP zDSyB5HdEdr@=QMK`^^GPeQZGOj$Q09G+8ia+)1)du^co~2}&kd-bZ~TcIiF{>%$-S zUu4M+U!=(2Fu0WrzNay{hzp!eOJD^YQ?nPhKzU}av=P7D4mKZS({Uz zNaNLUoA?E!Q!Z~Qgk$1`$Bt*wS{!8KWDWbvz&*3p5pB-A*&%^vX#EeG<>R zX1bkL^cb_HiXNz>dFVtjHsi0TA5R!`bzam06Bh(XG7l*KZ>nfA|AaPZ4g3CYikXt* zObCxlh~x1MMT`&mrJ3v(4oAaZvE$1#ZM9+jNK8m4<)#^Nm8OcZjpQS4BxJN#Q_PB*3O~t5 zYc3b2wmn z0X*|}Fy@C0HA$z{kfh+#>YeR3U|sry$4n-Jz06mCVA`5#!2z(-z_6~4mL`|u6-OFrHRP&} zl4Y4Iwu4L4L4e#v<_hk2Uaqt!zr(zOn%CRIBgH{%k2rW*mDFjUlgYllwUUNTZ_(zn zp=twR4atNQUhR*nL>A5_4r!YT5^S&`7RV0hE4>wF3!L@3ZB)cmp z;<8ydmxCV?pP&$)r;XV;AR)MfBWD_bvQVJ&(OGXJ5MsfH&o`d|@cp@j1-I0) zX!tfjT|s*sI(#6J@W~)#zJKR2PXEj^c)$n2a1)}#7U@l61xyC;my&nPc+uy|Z$BeB z_EvgGbSXYmr$4jU*i4A*&V{%aw2_F8BwO9nHB=_7@SMDT-_W0Dp`o2WQP|`NhdpGP zZnXjtSh1y>$$kXQ87JlTFWvs_kWe13yBC8QUv!00>~19%2D138#BJ%w%qmno@-rvZh*Op9?7sLj@d(PnOTcZJ#D4M6P>3K+%wrRB$3#P9lRmX`>< zF%ul9qQx(Cqb3t3nJ5q*>{OIMx zrs5RL-e+u3C;0E3mXNKF>3a@0oT5+U`jMv7TH)+gtkXB??b;!{64rNYcaMrgOVz*g zgJJfB%|V|!FQXhzfUwj$LwZ&*SO}|xr!xvR6hobh6N)CwmN~s$LPGn=gjqn-mjr;C zI-vpbZ!xaVs@Yn;F-p!xK_rne{_CH{L_OMmsBxN!JH2nC`FX}sG)IAnhNLdbP95A9 zBEU$lF?YyeW$ojKYlYa#JO_hyb4&Ab?H7B_Ok7G@HDRIp!$rq!MHI8ni^y=%eak1y z25q`0HqH~-r}*7MS^JYE%7FlLaXz0YDoS(z;2L&A3LK%MH}sE8y{ zFuz#$kO6_qIZ2O<VNkKz5i6T)=HrErirvp%Z+GNFsydvXcU7qa?}! zDh_+fcztHjmX%SDF{44vwaL;7H8nJb#GhI08L*-=CG0SwbiNe~zXD0u_uW}o$tR6u+@-%)JeT%w~`l|9#BzsS1G9MISa!>2SoAHjU z_fZvj1x{CM(GS79-X3LEI%)uY?4AFgh?4PA5*Um8i$F@_)$)CnQ@(#sK*il1s2=}2 zeKN3@goH=)|AUK^bBbfzuo8qNd3P{Y9>jnlaW~aRLixX=FO#lcy37uAZ7tO9rpjF@ zSFlvB#zbhi+0H_vNcqJ{x75G3P9EZ|rK|jCL#i|%j!sz$tIPd{mPcmt3x@?rO#Z@m zngVL^q>(%@@XV5V_P}337K6}ViXS&P-z%DTz1q~`*3znw|B8`TZGLs}%sI(I`KLN6mRWLf@pYk0EDmAvc2@+wE1cu}JR zlPv?BFSyo3id`$Z@ICo5?>hH0fZ!{hMyn8UJA9!y!dlz7HqS&pd(qXuG6bu%w^F>cp=u(E{w za6mS1L_wmjZ$-qi)`zPQvSU2|dc;)t%E$f`5eOuw>bJ@)NeYp^E$awrV3 zDq;m7OOZL{Cj>{0=41quJi?&^f+4nw5UDL}ggq zb4$O|R}5(KYItAZS}v4L2UL#S(b@ak;y-Q`&zqKX)}*7>YRMnW$GCSgQC=Z;NV^yg zrF>1equ+@1lbrFAd(fImkF_a!8{wkWg`#4BeVO*yxbAWM7LlG@`)bs(s=S75TYZ)) zvY0K^th_YlKal>RXR}?N5dV%8pg1=Ogbmt%7h;sCqhpHm|Fonwlg%ucVkS|-t=P=} zFW?}k3k0G5_D-1Q^Y= zdO2nM#{*0$cq#c=5d^2KMo;TRs{AUC7~3s(-3tyS{-i`Ct5 zY0vTgyPeX7GYHA?$N%EA)377&`tLLKvk~g@bZOF!F)C=fbP|pyw8tL!hX?zv>6XF4 zQ_c0Am0so#SC0q)>V)^byMYeGzm)Kv6PHnAKKKC1XlNq-?_DZ;IS$8%u1Sn$2)1Ky zF-xgJ#5*qv3GFkfK_5{`(y~u%XX8|(Q4a5>)H%B9!vPsI#aiQtu41TwT(A!3RwjdI ziW(^u=YInV{-kaK7!z;vBK>koCj!KovQSYvV!s0O z_jKfFyMa{|-pe|&wzsb)Vxz&pcGY5zQdN}A&uW4|I*So_dnPJNeT1`r$i_+AIGW70 z{4dL0))d{h1SQWmbuHZ$PxS2C-erN`Zf@|7K^I$gFSOpcT40I@SF5(I><05jmlwXR z2QZ<73rwyd(-F18~~9rZ}O zp1=Ga@Nh104&!xLO)TMBWho@~KV+QvqUTw4XN|3yci5=G^aH0gh6C3+G2+i2KXi;I zM;Aq@t0y~@IHl$c?~r2|=PkyNc(s`ju9mo~D{V%;s$`QxR>EC04VOim!@Fs7oBp(4;W~2O5sRV(6jnspM!m9by6lF4WT# zqyuwr4M#Mo;!}ZtIWrqMV{tNl?vbEGkLRYBgN8AIb#w|l>@XbE*NP}qB3CnnwZ%RH z&Au}3ol#w*`oTW6X3LoDfg*8Q2CkK`BodFwVOk%>q*ZK`2vn37R$}rZm03srnAqN6 z1Z92wedsAk#hB8VEdS0LXCgUNWd~TqQ&gE^`#!`Ji6f6DmI8M!2Zmcjp>P&Tkw?sW zZ?W8k03N^Bhc=QCo8O(Q;V4-5gPMXkKY^}T3gZe%=Dq$$&9L~S(9xU4N*^M;U)kIo z<3b=Y&(fWZDN?l=*Xbu)qzm-y@!B~L!v4moBCz;0AIIMlW@NnDS%t=}w$88~)ZEUB z;g15YC#*09R$2<=H{5#l+-J`_^>1Ry*QXDhN)U_vn7|^GgUf-ip~*`5KW_wH*$F$O zpNCtY_>b#?s4TXd1NzKaKjc-cnqwu<{}wl>N+|hr1#-!MI1CNboa04e+9K4dmoI?s zgU-#QwGvA-lDqKES?&pyiF?5z;f`521l+CeD=WCLO}3VT0K$WQjVub%*NrT_Dmk zx zRn7+T^xNX2vg1`M%8ChmB2_-ihSmR5FWjTw>q z;mJ+}EwncgM2xEp-H0?@PDGSNvzmx>#w@k*ArE1A7XOZr(gK!rl$+e%yej93b=tga&XF~jo$va z<*?ck??@wL5XhKsRv^&A{7Zvck4tIg_){iZ?bUO|oQqnMy-;_pi&}^efaf7x8WBQd=uc23Ampjpf%2k=Vl?V*I6Td{lQ$^r}Ava8f zk|0El!PtrbB1DO>B&-wJKg{2dbqmv0Yc7d z%vBn2fxhu#PGjakwR@brZ2f76woBSM7`r}JlB>194|pQfA)pEf@e!^Xkzt^dwvZR`jkCR#~s|q zXnQHBKCJ~1$zr(}JaUAFb+QZ{_~Xw{naAPEeJoq}!`zZ6HM0F?tEgQLk;XZig?SD+@p zlIJfWhXN&>0TqWlX5oioL5ltTb;ji}<57&C0(SZ9SFerDM;g7QcGrWkWF{svfGw%4 zgu%o$RLeuO;H3X8@ujJw>p<}~JLR=fX2JLnJ66O;O7(t4mD3qiOJiUcF22GeT_)q) z)YGH<5pw7msubqEGCW~>IzubCLc_A7XFbdF!uDF35j7wem4(pDjv?8OPSN*4@2uC7 zrzGTy?dmHV=ecE%_RC@z;nM8)-0AO^ zRhXKHnWNidJq4=+f%BJF%8^i>X)^2{5GdboiS^DpV=mtA41=w1kGIOQFeR^cOkuMe zPG$i~=-^7@h#W3Ti|R9`(+d&;3QkSVI>HE)hY4+i*r=pe2Tl0w&hHw-OOt1bD+&~I zU}R)+f>iap`OB}vP1$a%1O<;)vXP9)Ute2{SUI=Rb>pLQ6Ly<4_A(dNQ2A~wS1|>7 z(&<~>P_=6~y$;h}dVkWGdGEhx+=n9A^&2~oWGNdB{2T)vbt&k0p+(*FN|s18x=ed%>OHtXIcy)z_+0~llUoSSHa7pFOG_$U0rJO^ z`*(5c432}(+$^knwT#UO25k3aFLds5I^n+7_0AiS@%q$mi5b)a)lnOuiWzc?(s7k5 zmmET}qb+}Gf7jPwxqB~qacAya$+T@H^q~Cp_IOOK*zTs&vxfZ{q{SBt3o8&SMt*W4 z-=iImn!7TG-DAf_eEX`T60^=75@XRu--*SnDqUZ*u!Z~fmP9$C>G?%pGMsD{?U!z% z#6v%-Hp2_Dg0{G8da6B;K<0K#gYr7eY5_}RX4>hJGN;@&#o4# zdc(eB3IO&vc;R~Vz+WAX_UY>r0Y%|*{Sy(Od{uHMh^0+?Tdq^`@SAis65?GF)NM^6 zDZ%>`miI;z9UZritwXGAjlm1HHNU{+L3raa76xL4zF@R2S~1dSRV=^>k2N-mIQuC; zVT~`H>H1Zjx0((5XZ{jTfkU^F_cIrSt9P7;+MOFlDZfaiwCtc>?@^(vJRNw{%{R1m zNRcqe-2!rU4EwXc%Og@E711lwDe=6Mz!JUoFq^VoBhXNae{w#91hFWWlhLrQf zuW=qGCrqY z#2@0H0J-aP3Rq0-s|RO-QztBd-mI6oc=Yv&J4yuyD%!EsMZQwnlMQR7%NXh16==)L z=d!J8EQ=GRQ%P8AL`_Dx0rb6Alr4-S-3^pdiO$x>fetnpsGFZL#=c|o`1F?jBz?+J z1XL*E5|YHvBjDag$N@Q21F)xx;+)mN@TCjY`-2$dR!EGEW%JcO`gf4_O(aa!eSTImET{_i?skgL6o^mo-f=IW{dP~Io~B##~|@($=(ahBAf@$ zgE`p$@d8xuUm-`~EDy5DJuln-utm5W6Or{?1<}JLKPd40?iwmZW_puXi7>px>Ld*bp2CLF$ae{$M69}kk$#`lTpJ|@rC0BrsJ$H`6o z2@2SjkWczUb;jXP3GL>(D1-dVLSH6%=QUkL)ZHcI)-d=~(`p!+xx!BHe z4%LT`kmeC`)=Un$osR1{d&R1By#b)}{^&I|<>oo2R=cSxMr{NeNeV~GXJwLSpytdf z>&N~sh(W8HZ}^UkUDj---U%oag1mUU9kNY+K+u4H?p9O)Aj4)=)<8r~IartZYTnn; z0>G;SNz^lstHrKg?{L>RuC3UuUXIwC0%7!(zGeI3tAhzurgJz!*Lrx?m3WS(>|Pc+ zFo{Rhl%OQ8OvidTH5`abmP>iEMd^cF^Te3woML+~XgXKR*_}G>G1po-MU`hedDoNg)L>3nHQGk3E*iT-Bn(BP0edr}+E<%s*Aj$jExX3` z&}twgMVTrGj3qKWvF5__2VWYMBG&*qc)V1oM4%HdE)_m-;r-;kuv#1#hwa;Im^Ul| zv}?*cHHsLT48FEwR&RY#BjTd}xuSg_dm^)pP1O82PZOi{Il)E^Uc3Bf@m5LYt32Ai zC@2hV*s%1*iXeI_yu5Uh^vL~|a#jEJJd=M?2M_e;K_!#>1b0EFJSrK9+=d{@x^{fy z!rMR@TdQL4C*`ZpOMn@+YT+XyhAm9xFTnKi6a|bp>$2;rUkSN80CnCMVrw$tDSGOR zcCPI{9owC#1U|KQq*+W89WllG1-n{FH^)l^k@ix(tCh#{cIm3#ILoj#11bHY+s3rz zVN@Itp)+A$%wHL8N^kq{>O`KxcJ3rp*R!mH?Oe)375e4}293KrC!b_j@g(MypqxSPnQHJn3b_*A6=yMoLA3m}Z9APdA00;Q> z*CH-FkDd*<&pE0_ZZwBDjZ+!o1g0-|_xkx+?PL96!6a8G2EBk$cbPD~DcEZ(w~Cd~ z)P%UUhhCaOUNeNEdpws+jH-v8-z1uN6LzW)91jykyJw^_eH+q%RhRwj8dE7Q3JVQm zG5lH1PTj2jb%>`sI^5Mjpu5<~J?zxk4d9UjRyO$PNDkW-)PM7fl0ysB{<=A2M|Az8 z@>;r)*2zYm+P3Zh0zya^+=gpZLQM6$rjqy=jYuO7;2G}hI8|LikXyWE5|K=gY36W!^+A9W`kbawV z?Eyh}e3sVyi$`_pSv6nt8j_yvLSD00qQyAR^7EQ{1$Q#z@kF0Ac$bgHq_P}}0o{Mf zXm{yR>FIgxp5oUU^UTFeDBIq5ijzP$lp0?yr{Y+Lov##>n3BB1;X)oW`BGYxuj|@p zF#3)N@$Ii_`9w!xLQr%5dlv?~52c7?GoV?pqN|{x&4wdYv7w6JP zQZtW{8Nyg96Jw{6&^~-`k`G(2w|)#Ykd=?*E>eOttzrr^^na$dZs0!dVGKj^Ub9%A z$T@qknF&{l^trA%XnJ~}5N~o`hJ`NitF-)+k}{7NuG$aT@$g#Zl5It|1SBH}u8 zsWNZy-kN5A4UXSy z&ioXmLX4QlWUu2*cGS(96bsjAb>Qsv=$On1;f3?q*|5rBW@d&F{fG*nP2-I#U}&;u z_BI9I?D_(?&69-7m8rJUFW;9W5i}kid;fZMJ)-wr>+}V}=Fl?Y#e_x=-a9RffL2{G zZkRb(aR$35c*6AHO7+j<2Wt;RI}&W94a`yG9a*72~xf@05MPR z2gM>bqS1ms2b?&D&?0xS&>+JLXGiz#kRrTtr?ymaPQ_rh`^?97#{A#g<9#8uK;vV@{p-LC>)$!mv5dy6qGpfi^=5c}LAbdklbv@Lq1s>%GVwf=a z?(Uz&b{O^MkAi#FCeOj-A zZ<_=|R@m?dPShr6zt^7pgHn;W0By!Qsj9s1dcaWuK?43)ho1{@h0Pd#?CkGMPaidH z?8MlaNLac4gJY@7IhXU@hi%zS8)CP66_%$ST@N37)n&05Nqh@-0O3~^x`R^L)fb)` z;=#q=JK6qqNc=y^Goat_ZDWRWn zl3J2uo9*lig=Fum5b}8~zEc>=n~puDon^doZTt=%8c%5&;RY9b!KnN^3D!a>29J&F zcE9dQ;-31B)0~z);zh+p;BfxB{R4@1Oj1xbIjXlG=dQgD6MQALJEK=6t>Gz*S)|7I^4k-c4K z4T&EcpNqf^D+q6NmO1uq)|12r71bpCI|v-q?3rW*|0|R%*d>05{3nWLL1fbjv+aBx zk=~JS=k9<;nK__P%N4_GjavcU15iiZca7L`NR^v6CM&av~b~wO- zD$W{wTA)`43(+4_^1F+H0@<>!1Uba%&WS^08!8l&2vkWJf@m!suJ=2aynB7vDYrXF z1#)GAh_6OuW1;-Oc`pz6o^`i^j|sNb98;nA8i~>?Q5Gf;9g69YDMaJy)AgsY7*Ifl z4ij)|I?EkSsz#$6nfTH4I9c8& zcOHJO@N?t!IbhGwnP6VDj^a1@mEQtS1`fxAWPp=ttZLqrVW6*!7I>#WQF&yRX74lq zaioq`?=?N=Jz`Sk3%X_@{@X#0Co@;Ml?Au-fxC;#asl;t-q%Cq$v(HVLm+DwB`Ex4 zmzcW?MzM292IK%bC>pFe^Q__@&KgjON%p>V=NpMaplPU6+FJPj{Uc@5u_>~+@jTcJ zsro%w@m z-->3PVY1{}yrJ8|h7Dp(ijxYWi!V2!5gC1Z!e%|u4BPq&(1q?T*JEOe`j6`HbS~g! zM&k0lb>KFy(OmT)LSpU^V~}=C-$oc5A-?zXP@lv_-K|eQdK6CBpy$}=mD|CHg!OKY7+t*_pAnAe^WD*&L9yk5j*+(7(yLSBuU_$YAA;?EFQ zB0kZMk=CF4sxq7K^zAwxj&V`cv(vb>qYw=bHQqSw=~#(hn5}->;a(JP4lF#o7hmN& zD2>;Wk;*kBI|_qL8cx=j5u<_ti$RuYQ1woBQyyMR@qcE9VxkQ&@4aKqr#c8OUbcYK zJUzd5Yphjj%fH&0kx{OElI9|qgxw3DD^;c@HlyMnsGK#Ntjl&U_s$t;jptJqD&-c| zXH1Wo_6Qxiddja`O>`;pHr)MtR^Vc%nE)r$#;+Hmy8jG3MlJ@Hp7C&|AkV$G^LC(X zmO>945Rsg|*#D12Yr~wNn$NRNm|T!izCCG%0@i?IRr(*XK=hr&QYtC z?S9EU*SvY4H+OXse*Oy!NAOqipeDkxen|o`R3J2K4TT0CEt(wKxo}a zG*=fkyron}o+SOPq*9HPl9KXLh2%4ncT27*Y?6?Ev`U*o#&PWfKkg9R%RxpRpvAzJ9#r;X;RuP;D@cJsi<#2z>hc-hc3SOvP1 z0%Kt~Qj_9hqk9HnpfrpBs9r(H*S1YtYk{#C!Jg-i7fiFe_*wNSYkpN5Ns}NJ8`)RhJcGwby}A&r9y0 z7=CrS(R9tK^(&8D)Do7^SBwmE_XYCmg)UIn(x3&eu!?BFEn(Wi_tA zcH=Z&{31o*bP$xhw3rIPzZ!2m@de-E*|-R)29Dxb{tHLNhBwlx1$0f+kiSijr|58d zP!i>&2@#V!yDX9G6R{)!Vc8sCUkXd!dpEwvPWsj{9qEvGcJqvfYa{dA0)CiazvD zzOiOO$hBoB-UTnr0gu;!5ETKzZD+8tYi>blUyq||N^!JQMAI)v-UP(1mG^^scOQ5C zF7AMiyjDudTT*snmbk2Z#u)wE2j~4!G~^m0sg^84TakOmGwE*8@g>z|L4(gZwYW^x zG9<@?#GKXIBdK2v@~eeMH(SFP@VH=4#L{@aWXteR0R(rCD3Wqy{B~n#i-+>|8{uC7 z0vW_zq35p(&W^WL$z3I9p0gKKzJxqZA!M(mb7QyM2J!D*q0j<@W4L{2+T{fo&n$a!SfzeVxEdVY^NV3)J5H2?2G7)I(7EF%ruKIiRQ zVk<^Y51ucFjE;t{e2cdM)sRUZ=I_s0`*SKjM^@-e6iErK;Vdb82+7#SC39!p*`q_z zuTRYtRGJDbhgBuTaDTUAL(^0wSNkHDs<@gC&b8CWfUBKI*&RHn&c?mmo*9EOIIA~i z9NDA0znf{QyDsM-Ab|$D{rzMT+)h8yW>VSzu2d7b>S8VytI_YIB6RR+wFpA19m?EN zo#=n%T%M)oPplarJL3Mj%pjj%#x;a5ICAHU=f?M`H5#X#dK(IMd%yp`5f95uhWbJS zcR0z!ixT4`L3}J(-YYA>ULp}q*UHcn;YLY?2{FV1)hhfTWD+)>3~T6IkcLAYh;WA8Nj!nx&341w zJOP`Ul4_C%S~hwvMhaq5$;G3QmNMjQ;FZTNcoLEgPq7Q`f*2x147+SOD{BnxR~24c zNq;5DGa*-rb41%@71UW~Nyz`Qm?}&CfMizlz+y z`$#7-Jy+Gn$Bz#H5q$xMjZ_u#F6L^kUHdVK({uk`8byxD;!NvE@=|#ih6~$bt^UcG zrT9t7b`|Q50=B_p;>Y&6N*=Q{VHFihnduT$y3c09&=;rEolyOA^I@N!>UA5=@BJ=% z@~SC+IO-@T5BOW6Mc^4Mv_m$tH@in%cwJh#d%et17uu+HcR;R`GZ`ayI97n-eF5*b zzvNtpFS9ksdIei@K$Kf0dxa{1L{^y&pr|RKexJ{b@g-wVohZ}=f%b}tkjiILlM1-4$^*S|S_NU@;NzDQ;dz<- zmwgtEiS}ah&Xd!y8~xE$wQj5hMPU1ruBc;?-N%YYsSZvjC$-z@pBlapfteeozP)m+ zJF!Ydiox8BBW7GoOx46ag#V9={Y|^UoJx)p_h)hS;5r# z_M$`!X2)$2C?8E{hl%&D=E2W~E*GjRA#AAI?+>3;U0e`Q*G8E{Uf-M{uH^&c)~T2Fg^MRELjdC&cDW;FMA zKArTH+5D8f(+Yu-ofzUdtF-~_`|82=7H*=BLL)NjO}wvPHHJflqd0MaU^Wg0IL9M7 zJiClA(I)JL-Up_^Nd2N=^e!8PLeic_J zZO$7W^VFkh@IgJO#+-NV*R1}BcET*pW-CROs zAebIKBWKhd6LxuT#((}CpK*p1k{-dRgFf)bx0vxn?s;3DFc&-^_$z!)$>E@dFEbDN zQ1p3=<~IMa0qrPjXZ88e3-L@N;iLDS&l2w^^+IfJON&}6KFX(iL?OBKvCz><(dVo& z{-zYqJ)vDiMcCmb=g;?q&YjC9SAp{Mn-46po0TjM7QUrO{(*ue4E#ERDHKIJ<_e-; z)dhFMKkr{WWjYebsaB!Jg_Apb0MlZ0Y>H0!6i`cGd(5eoa=FI7;e2sXoAnMw!#WNp z!$5N~B{J}FLjAxug>!3gaGZ(vxtWI9%#te#?fcC8HA?(-^DYc&X(q<#hJuuqkmQiZ_J<=uw3Xnh3rEL(0qlwDSAQ?YK-7EVrK&9EthryC3S=FHve$x+3b^CK#` z)GTR)dUuwVmt=t>d)yF48GzEr#7OiwAM1G#9ooHcq>mK)eUBZ}Zy*jmyB%D=4Zi0xvHl_#k<1lZnRFc84u=Hm15_hz6jSXpC;bWw7(MEq zvgyMbWHmUY>3ZLDTBCSV48=xTB!c829f%x%icHQ5ahC{!<$VO*aYwR3aVq`1zCh@= zs4ZX&G9*@*|A2YViQ?o$K$U$!4s;@Kl)x>=PVZ{={5wpoUbkea&Zp^A>lGplNYhs# z1q2jmOmnOIOA(6j966*|?{9dzg59Z1`W{i(a+wRBtL*ZkNQUnxQq9+6Rj{Hr?_*73 z0zNUdkWo?Ocy;*ZpW{S?vSYSb=iiO?)D31wiubs$5X2*yxMY4p-`Cr`A#CaH<^+*FYaT)BTmQHzGm*L#N7J|HMN8g#AI+#IhE5{ z*DdBf75R@oJdG6apg#th=BeI>OOlS%eS@K+Alp-F~-_Zfqrc71qr*H)4n!VkN3E#!0FVPKz%le2uIhlzJ(i07_}(;uor?7G_C zm-3RvfvvkTr-xU;! zueRRPhdX(#uL6#c5UDXQ>v8_QlFV&dQkNU^kk0_kiU*;N)7KVuu2I9+bT=1IdzP-5 zLjX2r!~%x{ikshJ&{qG}y*cprxGAAj&z}a#ddqq+wn@18+cUlinJ~M!Fd3C+`!OP zl3iR(Xy8M z%zWqprS~dPFrrU)KNES#MB+@Bhxi(`5DRmAd__H3rop^h<9iT?vQs%R?MipTue#!ibHP{#;O|FM zly@pJ!H(kQzkqF!_-r~kF*$SgTSi43-Hz|i<7M1IOC0tel$k@Ca{yngMBt{ljZJk7 zvB1j=Q#C9wt9Po{>$nhoe~*$fSPRTcB*WWM$0|03zN#!djK&ni%XECxV95}msCM%9 z^fk;j(finPvx>W`(ozoM&mR2gfL=EnHE*>_$m4SUav50#3>K^@7FVtJ;Kds{I-#P_ z_N9fbCN+{tl*@Ze6Q6qr*f?S58MPFj^3efffa3dOjliaD<+in=e8~US0)*6Y6HEaP za41a);uCfnMfXqmJ?Fm!3JJYjk)V4gow?_ij)Ua&3-cq)%P#lF@9P$NFG=;`3lYx9 zCh8(1&Kqr>Z?r76DHV06TPE1?v*S1W8+5?zB^JK!uJ^OU z(9B*1vz}FTqaT|?HV?mkrMKPys(lk{v8zFwIfxmzAxQ!H;Ma+k6OhuEc6;8~vNgw? z-pR zq@8?ixj$%zluw_I0%nD=k@{7hVFNHM!;qBb^3Hf4e_8!HB1w@{=VIWrB;TvKKRR+h zNS2>7$#496n?rUf#gV4XDmZO+m_uMPwvBQslTcYVmYEkOsZ_>$GbWW4QSRg^Ztcjz zl_=#OVwu!rz=39-mdeVY)B|2)TytskJEjT@bHH<&k(MJ9I$Qe{X1sqX2~x_SHoAdJ zCWW{#QbonYsd$@1Ylw=_L>?=P?G_6sg_&`nQ6p8%#u8-_9cSy)9iyA1*^%aBV)_zC zO*1zHIV4sF7bP{`(;-7oYP9y;nauKynwQ1x5mp$lUf_hiQ}>YgG3PBQsoE?mk(QXg+b2CO zXGjyJ1h&~9+8ENZijBv}IuDU8Kcx{QNkGRUBI%Wv)`wjG%f@5qJPC7=0qfsghch!v z9T^vwdUWG!D%>cS=gLfP4p+Xtc#`S~gAC z#2r!Kunll>s8@(S4IPoZ_c9i$pt@|&`>7X-xE)2jzmFnJ?4CY{Q^ROnKe(aw1m)i* zP#O?oMHc}Nb1@eaR>>o+4H9v2#4vq-HD`FKI*AUtnZ>!#7UGD_Me8I`N74c)y`bly z-G1>L+Cay^D&0*3F!rfxU%EjzR`)IYExyRf2uehw?%gk5PlLJ90`+9$#DZoCBmby;k^p#_7M70R^zIhIvMl9LUvnl@ z$#_fsW)QffUt{Zx!c`iqc_Wlk5)-X9YN<@ja+I1L%=^V)Y#ps7EbA(mkkpz*_~mww zRX__1t;)m{7?sJbr`<&tR1nksq|+G@QCx#ZPjMH)Sl(AXsSX6~QyRgrBooqG*Y10s zt54hmdDSjfR5p~3rMi@~?JF2ESZX?L&{eB{(dDm(Q;6SFC(yWYT+cVhe zlAO!1)rGMT2a~FT@49&PjNQRXKGkHS0dHb#rnn%Qlv;n@RVge2SnRVrD~5@AeQ}+% zKjdT2M<4NC%XrEV$SdktK~v;j99>yDw#-!-l@xRoh4?EaBkqW?kB}jq3~jx;Y4LIC z3-8y8j|;akI+l(`ATY5|f=aNaOe#oBl)lVF8G}m+Gifmg*Ir}h(M3~#lfJ_!31LT& zWE)($B~_F1P=nL1WUr3fgbontGYk!nLn!&0D7kTh%dMM_DBz%5MpsZ#x&u4SPljoW zUD~lJQ$w;3H5jVxP1lV=N7N?6$?@`Vet3l1bZ3>K?S&Y7O`x(cec)wmM#Bz?(tOFG z0vC@|aN0}h?gD-7uhz4f{Y#!>XGZPP#ZK3 zDy_Kba~ibaZ+KUyHI~?D4TCd@(}s4+*GoI(dvOLF@IeQXn7Khrt*ZPL`d#!e-+PiJ z6Rm)&twhCOO$A#L708u3ijAcRtd<$&aZPllH6czP3s@I(c!c{#-^ksvy(t?PpgZ+9 zbBo4TKwe&){(X+&y5Fis9A|SKvn$u zU#c{z?qc+pJ95Eu)Q})!uU8qRN$!mAwKl*eI~J&RZ!}C|Db6Ne?=hWx5lu1EL< zJi58xDtDI?#AyLf4^08M75R`0YdcrH8G=Jv%!2b8Mi)UHtA+g;VX)ag}vd1O^Dh1u`BIdD~y zzMS!RrtVi+X0Ne^KBPh;T09d*Cqa*zK8E0A5M9B4bwz3Gn%~mAcQy0h4BC&3r3P62 zKGF@*7QuGZ27Q5VzmGjDVmsRQK=sa&JuGX8-&OxUWnsZj4d1Y;+;78K@TqXU{tI<$ z_qyWO^$>Hf#ow=`iIpg|!F_}OOWd~gLo#~Bv&h?XazhBXHq&Y((r*4%vwlO%BOI8$`K@ti7?X@$kj-S_p zusVe3G=}t8l8h>>hNI4ZG1)M|O2|ENeyN6RweH(LF36uB*be0hX4ASQh(ivkf;V5> z3s#~sS+Z{48`o?Cf{r`0%V{g8Ao%Eiy}wV^3yDs<7o6sFdOI9l!J!N|a0V_K?Ch`A zoi>#FV~X3X+IaT8E}x7Ah>O`-4Z3(NH}9151R1d!kINudW~SkWkBe=$wY}Ru;vsZ& zgsLT`gh0PptlLAT2pLRG<|=La##RRzysc>AKay4)PA8S#{_&jnIqtqCSA#Fyc0}d8 zrR&$NnS0ok+~*Bl=}b|qts$81lDxD8#!j(o&Gs#69nKF4URF>*J%cfC`RaY`5VR8C zRnFJXx4fMyp0oT9DCvJfoyWiuKW@QR+9~YCe7D8C2Gg(ElPV124vqKp%RX~)zxvKk zOk@2aQGULb1tzA@{jCki%#Nv;{=QAf73a7&eDmV$i?`Ya5oq;)2-+#4&n`yc#Y)}AM-Z|{axU=v+Kd>uW#F>6x2OE~`rtXyx@X->R( zPH{-PSZyJy#MERo9G~410K7w))J=)1OfT0YJ0QmLC#eV8hsT}He0Q0$dOG^u=uFJ! zH}jo5Cx;EEegvL(r&5*f{hO8hf9nP-PLYqd6yc88Q-snp0xPbgbV%)){ z>&m!hLYfBg-@orYXKPL20^Sexx2JYcS+v*lH#I(so5wR6F~m?3qJKSa5X9w$6xP57 z?pH6@QNX}La;B68+8(FdXyAS91(hmszx#Qj$%cE4J(B5O#mu8~N8FW|*rfmJ`Y z5F#}HFm8fN@1;)0x}5f`*PS*i5gKzbUEO{BFujK6hq~U6?zb;Dx4(z@qRLA1euw>s zGvD2k@ppb!BS1O`Z=yYdq{coDG^&H(gCaF>A%MHVQ&Yf0!<~4~SX7 z|MpCOFo`QchC)YGioCy+QsJ>*#^v&qMkA9?Y*SWtC0ddeF?DDIC$cuoPG1N+aT!yK z_G6COAC%=kcHHGwH*iNA`n`N8 zKWKo_3X0#h8SS7nh@@=fNdO%>ci^#c_>G=Hm>*desu?Qd`yHYwWH4O3Po^ggvKM#a zsJp%Yp91(dTvduBkrjdqaCdM#iGn}jIpD_%b6?x7?t%YilD#(ba6gg3@y?T}Zaczm zjr0CG_1%u=`vUgJL5-A$dX?1iMmX6b8;ISHP{r>l)b(_w!RNvI?&SJQcu;P!i~!Z| zi~ys#WLmY8cmnkvD8MV8r$ZWsR{eSs79=E62O|lu#@8^ii=ReIoH+jZbeHE#9=9I#jXU1|A z=>d%X?h9;u3%_YkLw14S=c$HG@VA&u(Khxs1&;WZ8~nkr_QD<}Woh;{6+AU_r;<$@ z8+K%3J&lRdXlldV7)CL^_VZ!yMyI^T+(GmXm$MS|f}BJWXF1K8RzeACjxm*s**UWK#lPUdE+!igZ(>33s3&Q*nIP&} ziT+JYlCQOf;^>Mq9P55BW|0L@Gd?_V!}{>4#z~&L!8w{Tf)jHpQpah-`jBw%$HjF8*8cQ7Bl{pW715~YMqcRJgRrOLKZMIxf zCZ~)o)H~2qXt$mge;(a*-!lIL^b^_$8{3w`!L4tehaXdEHWRaA4sBf>hZ#Jdw^Cv%M>S(AchxIWwr=bROZ$9k!^~cNzTuhxzoYxvKxLdH8hSV#2J7**>F_grF4BVnMt8|0`)E<>Y)I ziTX$P9X~AYQ^SS_4r}8=TA{_kfIKg#)m357uftFTA6i1^e-t-b#D)B8>tAa$n>^?% z=&P-M2(NJj70j-C3-pK-Bq6Y}}P8yHs&;NCWork=N`TcX9P7d zW+Y&$_vprcs)N(^cl<59rZ(-j6W%DeoqQsg28H!~RE}?=KyRd-{#hUkWm!O$h&4iE zJ7Y3);UP|gcCvVeDNnRIFvfl!BKhxv z_XWYSwiHm>89g7|7E{@oJ`Xo-cJVYdy1QWc{3xt=n}>f_y6-xNvQ9fEp*d%__S>Gu z3O8wU`Uzx>E7sp#Z8TW54%}=Bra2&x?-<@&P4vDr|H^%WN6B$dQ7_8zGR2pqp#L_| z@gSfF0!73ej}`~7@9uu^?*AXs$IbWan>Yb`(-|Eg3oZQk*RN#2ZO~hM(J_T9fx(?$ zjM4Tqw`YiQ#Tx+#Gf$_Unf2jn2jZUkVlOCK;mZjMD9l&GzPs+9BJYKZP9Y*3!>sL_ zG?!P{7~euO-5>`s9*PN}?*FE2ydhF3|ZT8!2$V>ymE!X!i9B0-GQ-uq7eEboYY_%CD4O%R-WMhqkDe5z`>7b)0 z;tRU4C2<&$SafBWy!|2W1v4CW+4#Pfx>Bd5;eZ@9UM0B%)$7@b#WccU3<{bl-}8xC zt3xhzJ|$c}!<{i^L=GWI(`2v53SLe%96Utul;vc8F9~cOe=wc7b9@?#T_3af1MC*Czq5t)gdG@=m=fVBhg7nX$GXV<01j}Rb;J% z1oW2;8sBK@yu{pQa4Bt#ehe+xpf;JOs~&U6$ghhIrjlm~UNXfNz74JI(+dt+Nv*i6 zkK;|8XVy!EO?v*3`p!h5zfRu)ru0w3VQsY(K+@=lx-Kn5O0F-AkL`$g?wYJ(qJxyz z7^hKR1~vB}d91L;o?Qc=j_u_8NNe@5rNIQ5LMUf-?oFV9VzlgDmTM^XXEnL;qt2}= zSTO!S!D!yXJY62Bxmb>An{$f*{lo?)RhzLT2G8dlPA>i(WI z>Gk`%>hPVk6EhS`q1VPu!)auJJO-Ig?@0SPV4|@EjLxPQ<#q2?Z#NH>Ky=lbn>WmjhBJ+!y;Eu|>Pub*|3IJpW_IdTY4e$A`@=n6Al zwS8qLB>kvBk^+nbG92AM*AYrJ?jBU^8EsnDZdVnR<(fF|p`_Mo`zvh_R}P7twk%1n ztwo2g-V@g*N_-m!Gy5B>=Y(Tu-5>!+vo%MQo9{xL;l1Zx;7!6%jXjmhONW?|6Xvsh zw|kRv%M-rSs%MG}P@>b&U!0z0Mk( zDSKKCuQ3XNt+=#ncBwHQO#NAylMbq}{+xjC@k07+%XUAE>r~Fx{n{;X8)Eq7ZM8=@ zEoDbGM4~nzkv7hWEQ>#eJD(5^^EyUlqJVD-D~6VSOgW^Br2N1a>f6bMc)x)=`}n>2 zAIJAYg7Yd1Qt_UdCu#V74n(FOhJ1ydvuqW0P&MRCey9k&zqE z`+?usMO<^Ad7@(=zknKV%mKarVK0=slcj2dIlO(VOX2UM344}jAH{s{Fga)Gp&%dl z{XrjnZ)3;~59iaPdvf!Vgw&j=0+g=58JzLgDs4{dn(>F~M1a2+!Gs`3I1VJ}vviJV z14b4fZA$RITXJGD3R4Cq4tA0_UwWQM3wAb%$SEmrUQf{2 z-`W^$o^c#YN`6tkhpcVB`^=&K(2Njwlg7ujVsPtJ;aHy2$9q?^c;aRd(VibQMBF`(c zex!@iuNlk^Y(y!vJRt7O1+@v{OGCQq)2&El1co?2a{4i0vbQbYohU(L{B&wE>Rhbj zU66A*#gEKbsK!+eA3Z=}27q;0$=5Q9@^&UKB6A@guW0y6vFq+~rfC?WGkc2}iJjjO zp}6dY8OS2of}3TDMwVL!bI{q_9uV=D6F)%)U@qdG+Wm zDLqBPWXvU_Un}<~#Jl6M2JjV8KgaW}s$sMH6e|;^%dpi0&GXel-P{@~JPebg)pTEp z-Ss3WsW-&>`)yD7u_HmG9!My+?t@OD<#cES*8ZqsVSGpP*;tciP=8wuDibBAw1$k+ zi`BmGgGb0FcVtikhsA#)-X?b)MvktR_0E~+1zmaUA5YM}RYJ+`D;q z5J1f<@G3+(D0Vd(G<4=$L2@61FKip$WU}KwCYUQ5*N^hpUcm0-K*x|3u76imQ_N2r z8v4_vBq6a@WU0{o=(xh<$jqi7(Eq^jilVTeL6p5cl=IxCc(Fa6rm1btT{o$UEm&WP zQ6xhEy%eTxc2!OU-YDa~-#(jGgG~RscxQ%AZu($QO}L~-4~P2MnL&4mEiz>9doS*% z!*?Q3F3R6OyVQSYd&zZi;ks^V^p8Hi`Fgb!-k4s{npEzDge@1|_<@u@cPJ-+94D3K z`(fZ~am=!fUUx*B5675;o~~nj9X~;a@k^^*PP|q}u|B=*S$`T+FnR4QJeoYFwnQzi zCv-I$G=btCND#3!eGI_uzJBB=+$FUfsVxMybwY+uh^j`HLgD^yFlEepcY{yRZS~=d zhoZubx;`-eZ!N%Q`vS{Yc)M#8I4WLVOtK&HVe$jL19)71{Cgwufa7;ayu}jyVVPVu zahntyTn>i|ZLkNjcN}86EIvMOMmRE#?tjXG3X)9tuDXxQfTqvi&Nk&`U zwVuX|!Cc~#9;`;w%P+nuZ3*MvKX?A~pUy$@kW*3qKr2zrR%XY^&u29s1AAP0ClBxD z#M@Ka3lUI8Mr={Ro+JWpSQ{-CcD8PF%1MAWYh3nzrKkAy6p4-mUGCSL!i*}fI1qnz zttJQ56m@QY3I+eHNKBe`i&DLAE*wX6T21Go^`@p3l(wh{M*N2PC`nqxUYpYVZ1ool z0Jfr5!r z_MC1<_WzdS6E%&Oq!FQ7yU%0?bDph6fGmZ(B{_*7WR_Cji?CmuOXBPejr}#gEkry- z=KEh?R;sdO0NsZs&P==e`1>PoR9;KiUFKa+we~|K|JEOaYNY}4hvbO%xUsYzx@dzQ zbJL{?r(zs5ZxB5m$Fs9mH>l+gTN0mY|_g?V^^re~+^IG!X@n$Q1hfm5eeH3Xi%iO^I?9CvEMSWp5_R`L_Pljr+?&fgQ89JbZ;GbwLdvaGu8>^l)g_YB)u&3+QFrQ=o`=U zRcrP`MIMU=_=K8_PQLSUfVZtWCQkCl{??X@gzpa9izX&YznU^3w$q2U*Wet}!slcX zal9Psh*@N+l1D`2f8VALbBiDytwggxpef24`+iR)ba4COR%%xtxnOCTeGT8g<%rL+ zV!T?oV}zJKogYAPjFC4PIY+L-QGE>sKB_cq_&~Y`?~lWSs zJa>_beIz)Q;5aD|n{IF!dxCP~T+SYF_fiRtSUvG}KHBuJw|S5`<=T_n9{Kx2E|V(Q z_O1P*KSH(>%)QCR6T;2*-ZNw}95smZ1lCe&gL{kfH@xY6Keh{ft?zUjQS5hb(cX@h z8zA*w;sCE~=NV6X3Ner7N7v0gK() z&fIOX#m+l3Jo?IqAtVv7W^a?L>KZp)pt?s5;(=I2p{PRY@uiZ_kJ|NpKv5f;GYPuvj3r48KBp*UL)u@8|B6cfsD1<22hKSjy7fIUL^0htX2*YP zBGQ>lGnrn!cQzTdPqMSOE6MsfU$5s|^Z*|Qce?X?T>SK4#$EY^ghP@c$mPd5Oa-_K zknUAXe@z>+PW!y~R6${3)#!^M@2>2_ zHyZm1g=+rnfyi^2h_zFC3P>>}T3Ob$r`?53XJ_*F3w8b=tNE7%sln2;hy9fwal^8u z{;#|t9$Jo%b>j?=J>w`6(|v*n4}JsA?u#U=3q*Ml2mGw2kQq2FG(V;SGsdb7HTv94S_ z4@EiU5|~HZq+z5bqf(^XnXOJ%jQ)|eJK5|fDljlGOcQTu}3g~CE`4x-) z0^9vd`L;4~cD-&KujrtwYHv4_Dk3g<{RBPF8G1qxRL1P42>Xr4QcR ztyu-Y7^_MneX;MBCL`w;*-PG6(&JO}(WIOcnesHTNjnJTx8*|LFGmbg$tr+(Z??sGYXUdGyT3W*firqLrqc>A^H9udSi8IhJJiViLH>ec*?H1 z9nVKn+f*X;BAJHG9;jZ+6zrD((hZdGvC}m8Df5c#4xt2}KCZ zSJ_M1-1*;x`~<5pv;{EFpTrO1&g54bt}$_GZ)dv}JiqCZ-Ik?!o;3NA%i>KAKKb~p z_YPAri5d(3-)H3zBvcP#>+U|88Fc7>`^@B8G9(#C8I%=`ow7C~2yc3)P6oQ?(PWKw&EH)x3mjU#fcBOl^e%TQ^ z@%S`qwc)IgU!<}|o+@;BY^z6{tB@TX9)*$LxkEC;KD$k34l%jS{_tiwf0HP$G`$%B zPZOS7V)tL&4`Q_xlvd8Z`Muy`lOw$AnKjZ`qIf5|vGxSxB=&}&^a%vjel>cix@@2` zAS<45X*D%T%*>sNw8gM+?GSL)-+KP(4TcY0|4&`_8Pr7E?g5+*O7o#Z=t%FqH)&Fo zhb}cB5_$~~Ix1BIA`t0C=_o{s)Ifq#L+?!>(wowQbWVKU^PV~HnK|Efc4qGn_wLO7 z|LwK+wR1`>v>8wug;|wI5%TmPqo9PkD>pv=ahj0wVvhN3VD?4N@6D7@8zo7eLnc8% z&(O*bcl>`kqgU8qmtnI1LHPDH$25*eq!Bl7C?O9Z8=q&Yz(Lc)Mhc)S_bmxJIVC)| zCxH2lTU~#Ii^5VAvWvrnJ3aM%F6K=(( zeT8=@xIV-(v6hrRD?*Gv)F-ul(x;f*l=^nm@xE%@m+`Xa0{y^>L5**5R+i*tlRgUwRbqJi0F6E zm)ED-TKuZAF{qQUpijn7J~gIM#ZW0mzhZ~u+=FS2k^cL(;`@K*&SyhzHF5Dv1_z2s z3jv$i3f#=SZzt6k9N;zfx031!VbGHGwQi|LiY|znd<~cN%4)p8u0^xO~dqO#sULU(vJHsYM!-g?N zvTiHZ5d@5^pxt3w9r-6{7svvY6vt-+2{Ah{Ji-^Emr^y6rQjk)LZm3S#8&SpRGg}~ zHkSOGo5)=OR^nMhM2x4+Sn2(+7T=@I;UQQWpGUzh{*x*O86ta#$%eO$ayTpQ_svCA z(1r@}?scKCdQh$77+(9?S^s6bKtC#LgIRZx&uP*-K=_yE+W7ll=4xl_)}Y|l=Fc>F z_lE!)<@l)4XSx)H*y?2LNK#GQ1t%a~e}b#6`L6+ELmoYHu0ar9Ix$qU4?V0|erA;; znV0C7oX*Ve2g^>#{!w!;2`*zg9#mli(=ayX)slB6r|fd1;2I4KH~ z?9Jcb1p(pvxMZr%MB%332dm3Ay2&^^*+Hd+nMG|JBOAn-7-T0(f~2c}a1fS@@sS7f z3%hCf>t2g?4$)4E_fw@#-e>M+D$L`F5|lOkb)M?xq3>BT0@junt7MazjE%fVjIj+L zxJr8APZ115S)c;PkG<8RSJ_tsLXGpvV+(g@qn)Q(y$EcZxOaN26UwjB|BdX%E){#d zDw{C_vi}6GnfB3iJ115&hl!xIud0(u|GF$CmieC6L*w(6EW^BTOr|mcB|##{k5=6_ z@vJ4c>)t_y$S~ty{^-LN>W9rHw4+^Hd*Y4vqWvMhyuSO8R|<{jWKAZbF_#V^)GgEmI5M%$c<2KBvMKW%r#0st==S#!w!AW)4!5rySKkAi(gK6?q| zct?))-~C_AF8%TCHRA0*h<%N(Egfp;rrk_Lw8Re%FzEY^v@57#CK>{=+naK72U{x& z7*V*b93OBC-fIb2H&8?}>YO(*-qbgh| zX3I;yv?DlGjUTW%7}Nc!-7esuQ@IO6CuZ*e35AO>K?eX%sxRBM}%%w9z80Q zkhIznDMmR63U9tid-DNwCprXK!YD2%cotN(@N=0rnLQeq0k`4a$9i%W6bwC!czJDO z@tab=dcLChNc1+atS`r%u+%KZV8vPX6?%uq$)tKM)fxqzsI}*l38H-jP6vJ7r%Omo z+-2ZdYAz8+}H%F!*s^r?A5V@l9KpVF$;Mvdi zF;g_cP2bh66M5v4w!1?_;}R*pu1ZL^PU7c;D0QvQ@K?2YSnX&mnJcp54Na4~{hcE+ zUkHSC;Oaj%l@1KI_ zT#i0i#nNf8Fphk;1VV2s?(txCuMCzGckQYE2(bk@`O*2$fr(JnB>O8_&uP1X037b@ zB&U1?`x~r0IB~6$!YQGD47&brgT~qr6btmL$Jw-&+f~+Yz705^WWDpRL5zrL{&=&< zJnQa%6SPKnLGK&-s|$yOE0#R~pgy#FYlYbI#~92FvpOB;C^Y_(9}VodmJxGeG*WCy zFU5#$&RnxE9PT*UggR`vJ`}s0`OFn%MYGgIU1sZz{q+a0Rx|Xc59wB&qpfodlLh{5bg?**!0&Jdt3KzQf$nzLIoymK zC*?Q7+Jo@}-$Y(2U+)iVf{*GG_2@K$lcw%k*WUp*0n%_RKRQhPe= zEu>z#n2p8(Ha>H@QuFn#RKHXj=@+CqdNe*+Iw{Ltuo9hzL=T~ukINTg0p&Mrwa+w%Af6(G9-TH= z6pwlTKAgUgcA1WkT2qc+oXTspczIBlQyW5J_6e(%WZj%{wIUNITzG%5!s#F!#vA-x zWn*FYO<8sY_QAq=r^K*m+Y+1wpWP=UK@Ys&S9<^5{KR{3#Mo|9o=UdKDr&Wc{H=)G za7dn9!^?x3=4Cck&6qcHuz7i`$vuQ@w$8Su>8P^lpp^nkdhh;vQW#bu>^Fifty*!Rr)@GO|E7jzTh4=8M z+^}2bD|I*Y_J;kyq1tR}jCJyNt%!A?47d6Q>kRCn-oEEX%pA%B0E(V5}JS& zK>R6tciT`eR~uKdC$Xb?7z=nbj`nwKRUvR0$wjXJRdgFQG?)DuK9p?kUHIq`C}YaIk@bThGvx`Nrl z`h)x!+P|xG#QLu4H<dP*G(`IY;NT>IjGUqzBm~E|@X^mG7?I@63L^c76HBn;D z`-o&x5Qmt5K_736ltPU-BQ!JnCCpnSZx$Nf<5SkgR^w`keDK++-WpQ#_Q%E8BxT&B z9VG^=9Ieg245AS|oU;S^JEz@7 zVNnXwR&4J_2WTJj{q?*1c;WUa;HW>lx(KGL-uQwtVd%@&BuU}QOp@&P38al0V8;8p zcc{`7hN{N_Ocjfla71JzFX{DFNzP~PQNRT?1(~wCw!o}pGAR!Fu>{fcNw$Ml#*;m! zJ$hCg7lit~6Z)?TH2@ram~(bokX?Zcqx7Om4y9hY{-WBeX&)B&TB*pw6EeEG zsCl9c7qShK5!!kPTu``VIFa(;LKsVpgD zcQLsoOG+D=<{eNBU^X${4hmDe+B$Zj5kv!+=K3g@Do;=Dnogw6N!0xXvMYf*po6FS zg{}JDWjx3^qXmI4k9D-joVZx#1l`xECh2tqZE;1>+G+cRi4H>C^C}b6d8m`fTTbN+G#Xl8krfoxlrj(FOSk9rCmkxGr z)v=nHug9x=p2*;}3q%*!x~Ws@;hzpP3mSaLe}FIHD6kpE;#|!ol9W5r)%)GFyCo%y zx^NY48+NdKlSU#YQ)Nlcq7$_Bu}|YrC&;72jp*J_Vi#)4e3x1VtW}F$n15piu9FOQ zfP>u>M$Y8z6zeuuQj$N>Q11FRN9-(N{_kTL{rZmJW$^kScS8*ob-P?bbIhxV$svxR z(7bMP`6JifM%}(^j#|HGW-3_osE`eO2YcX(cKmU@Sm1j?IE;4?n3>|nwNw5)dI$7-~E>)DL|56~&J2q-645o=xJ6 zyHk}czL|)U&gNLUjaPjvVcD9U+ezstMNfPm?#wFULQ=L?l4g6(?r?tQddik%j3MI* z1BsA3e;$jK(!zW9U~$aPpHuA3S{=UwPUORXxA2O7Qktc!&!`to-TmQV$q`U)z3T>F zxscR3pAkNe`ne#N{ieF?tx2WOyQ|nQs{CWJw5hTm3sBI~jYm)ua0u90y1=G38GWr6 zpm$~NBP{F6s4u<8d4g~p!0dnF_N)6QxWi|g#)F{6B|gxopX?wyYP+H;^^U-Aw#9u-{13uW|CV3W8xcJrokfz zA@-y(08qW#AmF~X+VBy(=FHao->~Qesqp)DRO%jbH6O}j4EQgezQFan1TVhf$o z;y{UyzVbe(YBq@KX!?dG$*9aA1Na=kTxFaPiyAl@) z4y_EAS@t1*R`P851a6cM%5Odf0Z2OTMbPFe$?*y;kh_BJZU>8V=VC?Ox% zA42h`t3}7bDYg6|#P>|MSKdjvs_?j(c56?6u=m1bLLrM(D(8C>%nwS>Ccu78P>A!g%)CoT>9zwD76>E3mfFB#TN)+{mOE z58ai`d=kvUpoJquKaLP4aMefJlMzb)O6%G~ssFbsRH^acpW*JBy@>r2BCG2@otua0%{%y9XUKI0SchcXxM(;10o^!QI_mg1Zbd9P;e0UGVSTmbj^{n*1a2zfuj zIQ#%A!M$&uaE77ppK%;T)f^RVj2&I{?2SH{Sld_`(K{H}8yQ(UnA$jAd<5~oe~HCR zNzGB%-bl~U%*Oh=l9`p!d*z1@%#6&e`z`g1tOuE)%&Z3~h2NRD4$}PD823Yi*|-ji zSDutRssbInmX_&bgs+McL^JR331C%61YcU zk)P?`XOy}mzlqA1QFQ=ek2->6eK90g=qI1Wp<&_$BR^ecO>#YCX0EL-r)4d#AD)k$ zo05=Fh3CERd;aJ0CW7)9qVkE9DPPFm&lsY^Y~LjQb2Z+ACidsQD)L38@45e~B&$jV zci?w<+cK}-@W$hBCd9Ln-pB?^`y)Lq=tiqcLedCrdgeEanOuil@a=ey+o?w0Y-nO1 z@i-F{VJVRwcc${XF!!u24^TkyB0aC0%xR>SovX@08A_=mry{4-UQhZP<!lrczrF)$Gx#LidJPNW zHsy3RCT7yvbg`7ciAG?2kAdV&WL(QJJ;R{O*TaF=8pM-B)(A*_8ars-oPsML)OHqb z#d=cwYnYSkCyF#!$X0vB5m5Es4@PAW3w6&mE?Z6|-NKiQvBZ<6(9LJQV^6A<;<(}o z+vG*JIq=U!5a5OY9=O%yr-f5TPsoH-G@cq{Dc~Jup*mr2+Z*F~zbu&kR3JJvOo@4| z-6k36s?OB5UnmlwnpV62%l(qLuL@gi6jwg*v#Tx>Zp{-$k?{j+B;GAul0RQf>N%ml;K3>-cg-#3|z)!4Xx}2l#QI&9I|2kz=?U|#(CW)@yMI?uXPNC`( zzTlNM=|ZuVAUji&gT2sIC&DG1^8v%N`X2@v>*$uO?^tc&SysA9&+%SsY%Ydsy}i19 z_z{DFy&d7)T87K@EG8^uKoz0z;j!LhvzqN4e31gks1Kg=UarXP%5$#2pu&==R1bjI{`c)I04KY<+S>eY~;=FSNCfZ+iDq&DXJQM>lF5>_EM zI<;$z0{ca?)6Tkx%*?d)ppx%4nvoQmFC-qkH{&Jb=2WzvtlAF`9 zokYu-R(*r#w{U%G{!oG@9|=i(9)6#sr~Z$&Y-xX7VSYBR&E9I*ZlA~aX~3qff^Z6N zJapO9?QRe#%I*=yINjTv_?tD!E_APN8mN`0V6hV5u{QN@)#Glr+{fj4LK4vtu-D4y zKJn5uKVlq|RuR=f><0|!;)ETZXG%o0*Tz&ldn{&cu0+rIz7WN~!I~rn)M@8i2ND4& zSP0!nOIYk_8&@?1ZV7DIXyr;`XaSu;rFT16FLuv@iE1h_rowkS;H&y{#+LoU5m->& zX}@Rc7f?UN>Ut#^gHN2GgIVyIQ|yxk$_t$w)An3%Oovacr8*%g+T;xXH@GXOe#81L z0);3*jwLB1JK^&6OgS`T8Y7~CZF9X;8&;gZB9Q#8yh8TVSF}bS$wl*AR}E=3K7_B! z?q5RYI8!Jy)&||2l3875VGz-{OxwsdL4w?a%Um-QIohnO)9QTvgX>hdp$EUTH&&CW zNRYYMwyBx?Oh02?!QY~D1SBui#89|%=v+Cm6jbgiXz}x#Pqxc;3SKq-75O;5UkWg| zFW9qRb(x*U`b#W@ex96b#ou9?uDy2sEsg}dCQ?n@>bt;v*e)z$J(P)w2_@r*DL0%k zsj7LG?kn4#A(L{0jM~Db`b+&QYl16QWNc_C9JPu^vt?ZvnGGSGQTz1>i(*W~D}(@B zKq_55QUMZmvA3vPzPCs;AXO}Z#e_*frJ*o$gZ0|LddDUq7{y_<(vwtczpZ+0UB}3T zH#!9Sd`c2eC)Mg6QTp;`2;T6jwb|t7vgHQcG@jcjCOaa0Rdj^~-!4|xS`2Xv%vI^?yvK-fIVsi2${(Tmbg_U`dZ{h?PZJ|ps zQAs1lI%dycz;csK&grU;5`ZF{(*RSlNjJeY>4F;F`%y*(a-T5v=p3MFA6h_n0_Yt0 zYWBMQP-}T-u716LqR>D39qd7ubYdnR+E?u<6Rvgxe04b(I;O`n+Fn{fGrx~JV3~*z zwk}2mO#0NSsZ{IGf?n$7^Q;aHRaT*Q)GJ~t+Ut|hp8PJiFRjiU7236Gjav4+&DsuA6Io0M zg%-s5k4op{ikMZgo1JezSFoH=Q)s2jeqxengiWdE7ZrF5HpzqPO_GxX zq_`(PG5F&erJajdVt)&qavD7H=X$D?%;E+eKpT%cocqg?WI7|B95C{Dvv`B-7UtNGw z==1%}@V#T9z_{*LndOm=2%@Pz-GYXSrc)>xVeHi%uV@H`+pqDs@`*Mq2ZKVC{m^yl z6p$4uKeq@AN30oE)=oRG_^;=`FynMlovkFYEj|ROgY#@N3?p>7+*fW8O5o6Zqo_hm zbV4y*`fr5TY*1mSM49C|5y0JXXMIm9tT8O~tlsn2qzvmgnVbwKc{Gn-p!OF~15lx# z7|W#oD+57ZOMUF}l|4u7R0wc$vu;&KJv4`WoDS2B|M@A)XI*nm^hLUGuVbAZwPtif zudsh_UF<-+#Urt>!dv+|;{u6njEzF_ws(S}iOXQGTnw{j4xeH0VzTNc-gCB3i%xl9 z2vsB5!elGL3ESgkZv=h|Fwfa~7(uUa?Ck^x(IzdkW1V~68KA~}> zNT~Yc2i|Fux~Rx$(RLuDU%;T1W;{zZPwQkqZjCRBu=g84=TKFnmqp1|H~piv$YP-vev{jG1UeZjcfSrV*zACwMV*p z#z8%Et*t~08IghVz`uHEM5F2LFgAfm6|2t0L_Lv8y-^Dl)#UVHW?_^pX#iga;lQ%Z zNCH?Fc)$Fe+Foa!|L@ZC;7Ia1Q+!b3w`+yp>SfV9fN0BA3uNf9J<*xrSt|K}#?eY? zJo#*;v^I8Dq^SDm&xS4$Yi@p(8gd5Wa&Ze+E%IJo6>HJbsGIXV9$gVK5%@zu^U@6?F-m(OM1&* z8jX{o)=PsGIkOMo=J!JkX&hU+I*9|-?yDCGw}T4|_X~|Og(iwVsAu28=K@Y#N)0Bc zzPwM<0UC(EQ|Pw2A##2s2QC@7g}4$w@6Je>uTCyxQ3uYI$(Um1 zo5V+t?Vc?tQ(^9f6sz)^M?QVjutytSu16nd$-Ml~><%_hc6w$!coBMZNE%hOsXmhw z^o2$9iQ=U6jba%MzVVEb@PF;Nyp1W?OvfN24@Fz*kRUWHu%xz540mLit(Y+CBjuqc4vnvCs6(K~nr>_P^9v=?BvCF#pJrxSW-`@9e)Z^V4WRX!8 z8hWS?p*j#~d$e(<3@nh;TFZ%fHwBC~hEx~vZZK;BZa*QQ>(6n!{0LLb(v~mOYsp@i^^!T^fqRv+(rDacDZ8268@44e z`jOkS%yGM)8_bM|JsnqU-%UqkHZ5&DQ+wKVgfV5E^O9+(5tzx0%e1z^VQL19xPgMT zwuVMT%5gVX@;r6Jl*{QU2%D5Y=%tB-SW&-*^VmraFdONv4m{KITm`u>49Mk3FSol- zjJu~DJ>oz4kb}orqa>$+y}Z~^NL#97HW)zC-5x=m8@u_Ntt}5pmtK?{uSTu3XvxWxb>W+{9Y{q?3#YKF?$Z}}e7aVM{ESWfTADATEsALIUkiB*I ziKix4k6I<3ad)%cO3Pa^Wg>!*cso2HUhDH!_vJPs5d={E;2M{L7ZRKAP)v-XZOv^v zV5|FPlPP`OrJ=nfq(xp5Dwe!IdZHoinar;tNz3IC^mgvSz58dl4HGqB>iHJ zz%I-rnZjsmeugW%?sAs0w0_E4x?8FmJl$gLMk1A1q`>qh{zQWI?3Z;~lahO~g=MBz ziV-LOjXG`9^?}vIse6Qe2c0>4z9Nwh9qL)74nTngszmIkLO0v$InV#9l9(rY;Z5T2 zMTqSv5W3tSE`%03+TSK|o7*48sADi1{L#=0vJlr~D&KC!qYeVABul+0?z?j$6pkbf zDG@aaTP)dj|4?el!;U1UQXT0lO#<1GwIR%H#`%mVZKbc{fOlmZqo^m3a1zvQmwy-@ z!Ex4PD4vU+1Di}mzGkCv0h<>ugq~k~7)=f=jlEnVnYDP(ljgxkP=gx+s_erD*fkE0 zht}3X4Mtsf<0ZJt{_*=#ibHqjLHup^=65LHV|KA&WBC5E2SoFtA|0`LQ@5$26ij8y zrPf{(2RJ7U{yLzj9F;qSC#rFsET`+VO>MDZ*FVp|S)>|{RcLdqe$Y)HKOUG2;m;MC zvTR4>2=AQ}baVv8er0)zJtW@AiR_js9VQk$^dkB=Fu| zOg%qm;7AncyKUcR%nnUX6Te{s_wYN{ko(z{X%J8q?K7WTzaZ%%2O;IrM2$s(+Ok3_ z|68zLg5)f%}zw=P?(yMy@bAKy8|hfymMg|Nh~O73{A@i z<+?W2K4v6v;W}^x&Vt3|TLsZ{qVdK~dB?9}1Z3^60IWy+z6XljH^#GAVR%!)Gv3@g zvXp2GRa~M(jq+OFD|aVj;^X482V8nTn~JIS;`{oA4==5*pzp4Y>UOgZ({414v{yHi z!5RWZ(W@Og8B)oGoWkJSbq4q&j2|<@uKp{Hxk||Q0SEJui>(-W+s(+1SJ=Z5%Gb6| zCyN!GJJO(!aLFqSH7!28dgvG zKEH*K6#Gb*xzljJcr8pMCetx$DQceugU_cxsXivR%=|jp zKWa*TH1ilNHJ+d$r!YUNAtnBWV2&3#Zl4|SHFNzY*#8){##xuM)U*CqvwyeyAz@7U z?{ovFqFBd-ynz*kK+d?^me8Q~N%-5(Wmd;3bpp~XD%D!-gHi$J^E&g}s%#>xXCc5E z-<9F2_Nc10P=c>b>Ovbz5M(hP4h41)xo@MAa*){j$&t2*Id0DdxW9JnrP+(Fa{+o9 zRdg$;#p8{0_s;Ts5|b*$KW8{M4!|Be-yu?w#dXG`5g?MmOLaJz;>B5NkHolSj2P~h z3!gg$>@Moa`j~%@@JleEkfKNTuknxMHpH?M8STTRfXY|G_fk8>S(tVU0veXYsL7~Y z(XI$Sjq%X|ajqXsn&=zPu0i^rq3T%E2t7=urpE(r41cbUpdFu(eD09f^z<*hoxK>j zRx6e$>P{w!PS`DMh3{5VA0U+4TnXA|t}rqiKD5T@n3lOtJ|(HkC*X25-`x;0RY&ra z1cPNk95V^)d1_d@(G*Y54U#`^)Y5B)tHmhMC4{lUGL|h`ayH2PGTpEidx)PflDD1{v0;1i}CPcw4VgV z>Zc}YLiVD3%}7dyCNySB?SbV)fx^yL6UUh`9Xy>ZSXmAcT!7Hm-)$8R}5$P0~|s`t-@g;4$( z=a#QOaWPT8a^%b29`K?mRV5*+yC2B5b-3A9-P&lY`18{1Gq#4>m>RhqwXv85gx29$ zx@GLHVa-fwF@Rec;vzi&4(rA)r>_Y{qX*bPK5~Q&Ym!3f^}dqXh~asS>u&%`E#qui zS_k$sp<6#EK7`5o%+kdyb~w&+vfl{>Na$eB*Q{!;rg zpIO_;fg06#b(}4O_!BlgkE*5MoRWG3eX@I6R8c+WS1O4Re=53Mjq`{u=F#!B+3RgF zYv!RkcwWEifI;#Ph_(?yBMq{FSe1+;oxu1_gepAV!+fUd4R=s}KuOl4*I0$fqAsmZ zz~8cv?#RChaKdXg0QcG2W9_ilHIv-VdQeXKbTMv#t^8-5D3Njhy#84Hkz>bed%-T6 z2bRyoZ|m_=tp@JN+sv_=p|`6W6ff%R6V9H21IRXZt(k@U=J`u}{$e_0HapStAey@| zQT&YQWaTHMRjCS}rw^>5u38R|BYqDzzYhE5_+)7c^!h2*EY*!98xwzTr}6{5*%u{( z=&pK*qx%hCt)a%ZgiXV~6K-cJx$shh$B>*XsbkXr8+Dj(_-~Bi$A1tB%~9r9iOfwx zm#ko8xZ=sDJ`Yf0`PfA)R!5Ou8RPNW`fc@n1YYV)@uzRSFSd1RmqQwf#n~PqTpl|t zw;*mVzM9Vm9!0aC23vBDQ1!^Sj>1lXVd& z_)5)Eq)gVh0BdgCT>~xO@{iQ$5pBwGntb8RL5yiKF2>f5ws!k)E6QI6R?U0TDScyS zDjyAXR`P+Rl->tt#)Z_egZ|6?5nY$zx2X=elv|OIoWH@#JHT%HO4q~U-6NK5 zE>6}OLa5FpoEqAQ!9x7O)N6g6WOeSF*M)u084zt{23zs#Xm4tV9lb%h=3Yd~=RZ{J z4pe#q&nyg!7hRL!;2KLIpOF?LS?zz5m@Sc}}XQK`tFPad%B9!StK z$V?&bd{a@ONus6k+dwir{!|>g8z^0|O@f=A`btvZ+0Tr2o}-%m%=D_&Q^Qi&Qd|u4 zIYdfC&A0h4s}KutukEN>+nHi$rIWlbk2sw_1}3GH$|!(O1U3)lf+0guw9ok`#ljUD zK|1y|Mq*yj$G$S+bYc7j$cDAMf45^*&lwUNG!-ipw7u3@I_xAv4~VYf*!xw1%~8TxA0;?Qcp zwTt9&6gHQ~aiAsScUdZ1pORO5rei4QgiOL`K>F{SIAa~r2pN&8NozndqF>*5zgE9a z$lrk0A%9v~RABtN@MsvS%-XMsxTTQx6TYhulm7mnY8xw=>37hJhY|=8LL{H9(O1s| ze_T-dL5bBQ6VdRXzj^NeLk&lE0S=47EYTJvh=*bbJ$&sUEqIB6Vs$M@sg<#92zWF6ng~ zQa-d~lk)c?z@>V*$FWR2j(8(i?yEU_k%h}QRz3Fm1JA5l6 z25v?e1perqBO5os|AzEMRnYTA$M9zi&z#+0FS`-nxV-e-+X;C>6c{>}jY)lag%Hn` z&~6&T+L_G|kjboU^JmlehvbDv4LEpKSI*_+B(-ossL~jZc2C@ZXkw=Q2 zt~ueD>_ex0PANEDp3rVf+v)#t-pQswBwa3dz<7P6YIgqv&s^szUI%m}p*I`QRQPWW z^Mrv{dN48Fh!H2G5q@u=8AfG zK?c8Z{mox^tI@0{neNANrqTMV0`M0>TK~=2RW?x zd;BfNHp<&vz$2v?ZJjE-2 zwg?rp-hlch%yTvK{y1V!FZL?&q9T3NO%pkZ2*8JnK)R)vp=NV{KHWw2B=(O(n^s=-3bC6sBU-Tze=r;TX!xLsYl;UW|Co8{v;FVD19WiUmMs0 z8kmq;5$~64uOo$SIm89Hqn527Pl995AH(Y3wAAJl!+)(6^t5H{J#A_wybD73HJo8< zE<=;G?JV){w3=Tt=WlorMGqiUDkvu0Y*=?DN7BwKsFZEjgdn8w%OyNKY~QZY{N zBEu>zsXpwVnKXLmWbmAp*%;A?U2b5`=Z7qceva?~uTH&l-u0@%LL!BQr zV_%d^SyEecIwbz&epu&!izcodjnm;7ZJei7^I*k!yS$#OQYPUO=wt<35`a9{G8&Q0 z74oeSxY?=vp{AsbrEztsM|nmUu8nev65+1}t8~b_(?YhG<6w?$1Zv%QAVcXbkL7er zo&G2}On>xtPU>wo!U1m?!_z<3!N(8d(iVh|zN$gTaF*O@ZWk%rLw}>&8|dz#G!))d zTOwtzkKqhp`>92d>^XSH1`3~v&btPU9uz&WwuhI8<<$KEpS3LaPYV*7q`_+NhmmCm zbx2O%agai}bug~A_kowlM2JM%urhY?{o($p2e9}H2gO-DjI>Y^RobNV&c1`DtTSnW z0v?3Jg)4{k4&o4FN%Le={=V+s=u$_GZ$7i1_R|isoCv6LAhaCbft3cT|>>teMKfLH3q8Ns!PSC>$aMmW0es&Y?%kE>0Ioc!6wo#-js`T$jTU^E#jCCR+)Rd z$HuJVfi7FRTCUe{(=8L+Ex2p#JyG6psBQ{nk;m%0Zu5L&S-q+KUaQR~4 zVix_oOVVZ~nU(vrq1xRr6qy?vqt#JL0*&j17gGq4sv>*fiPYzr=2w`;!hf8S@H}2H zVGa+P94qnB2+o9#R9|l0*7kn%H0EHM*9q88p9nXlN^lZvGB2w2Z%`+}5q=_HGQ?QF z(=1_eB%mf_2yDwa>7TBo)~oZ?*y%bGWmgi2{;9?@&i^#|BH!M5%PoPw%J1Qq9^~~W zU2{mIm1xvvt<&a|%w0i-jvGlh4$86yYQn)&Wzc^@Gh)~z(>E&0CRl&Uv6=P7U#jud zbD+~}LRG&{vs>zs~fMwq!UAj?#U z``Q?ZosM|gtarM6AuvxQ>D&AmF&#S3lW49*S;q$0<+~F>9zT=HM{~1d(YS)ImI3u+ zwQw{!zk?nj^0QN{=t=y%*Rg_P5=#(jt@5B9D<-`=Izht|YW&uY_`X`F5!yN0gP8LE zPu0Jf9pCN|W&a0?gY{-0aAl~ZNSR803YMb|H6els)yad&;H@(AZ0hzd0=BUF0#hQb z@!|$dX)}}e18xKG{yU{+jmHMw1H1nNR?oi+kcNaEuCcPp2p=w|^&h!VD#!x#C04&+ z+}7*bJy5pa!&*wdO}IHDXGy{ASl7fB>$?*nG@P)-rQ^ z)heFa)|7A(T=>TX!s@M-5ov7OJvy3{xP(#Bi7D%|>@U`lf=bJ++5TE1PDDweJR^)p z@adROra+I6C%>uYH7{XAdv&Rq=UdI$!Gl%PU#+b#tBpB>xj58|e+VJ&#NccAov2Qj z5ctKs{AG3@&a-N8jf=9)k27)gr~amjX1c$X*{&W-z-HsVRaMgaMUIkLPntnX%$MFD zb|CvqC!G$Ve015yO3whe*WP?8^;*>Afwr;B-1o-**MZail)txm0x0g^nr?cK zRV;ypM<$!IOk+b)`3Tr|&N{#FdN^Z~vhM6^|5S0d@#siab31DUc>LwN zGlN5LhwxlJe!x-gX&>zNej_^-6;0F33j!01u#dCXtw-M5JH5&?@1m4 zoL^Ur2^Q*t4#jFWO{q&2AD|WtqsNIx@Vt1oH15Cemf_CMuq_&l1z)k&`WHRq{f6Hg zA<-^fP5#uW<$5uSD&oGj^TH<36KVUotB|TPq+Pbs)BT+wH0hgb<;L~*gMbUN2x(9j zY5J65eB8N#F=K0L!n)4wVWsnAoXH^flNek|BS0U#oQIgjm2|w}T*d8Aotn}3ZYEuG z4zoT7?*>Me8;`Jpl?NuXhHKv~@TQ2_Y_b}xy!|;pn?i?J?J4ju0;ni-2q|s0hvauk zkBwEl5~^Jh8PI-&h`FFZsO$SS149DsJHg{B!SQkiCac;}Cz(Wll{g?A4`y6(WfDX@ zT8h-XR<#O(^CU2?@5`9YJsfdG|J)^DTb(a1D*_LA07R3n-N#y+@Pxyjn?~B zLv+1=bvB=3pk`Ql@ccmhK44F}r#rCBr|6U7t>+Ha5qS5kr9i|C29DI8?^sj;cICLO zDZgiIe8Dn+s2VAUzdINsCQg<5m25!Sb#0OVf?^TwlN(A&;#<|9LNW^bwzA^yZVl8W zw8^q~qtMt)+tym&+A<;v%R%ztcbjx5IaGJ8V^;e#$we&WvLa;O$*gs11>n=R*~I^g zg>wyQ72PQs3Fmxe5=Bg`Y*Ll`MZxzXgU03|~2?toWj?*!pt{5)M7bfEv1aMsjx#7SXLp4wM=#@j+nV*g5cv}KUAl90bI z+du|Lz`9N^-1*z9KS}ehe-qz)VI8eZO}Y8py@F$8+aBoSCZsA}esiI2SU>L3ib#YZ zkMW*-Xz7p2P=DK5kj5ONhFx+PgKGV7+)x=%jm((Fbi!O*sm`C#z_l`19uKn{TsEy&d!T3J#C7O3h? zl%$~5?)_VB;^!Kx)5wRsU+cAM%$26QW3}77I;8IeK?dGe(xWDdPe33Ec?KmuogOO2 zOck2L*`y1BU$&QvxQ$6*0cfu< z@-bTKZ&DNMt`5C@mPmE z!iYBALck_uAu$9i5;Eh~KvJU&wxX>^_)HC!0JDR9Q}X9)S+M$T&MRKdM8|+pu^)*{ zxMRC6QNh#Y zx=&06@BdqyH(1`Y++lon{%VxiJsQ*1a#$-(He%|V_+&>4>DT>8rW56KY0L=*!|Dvi zWpn8VLAOf}6Z!|pltITF`5qDOk4x+<2KU6L!EnDC!g>U0ilaq$1;urHH*PPk@XuD2 z3I%2LKP)OF(wlz(5>wQCuzChfUT*i|K(qziZ%@bT`W-kTMHH&+E*EQf-_{24{{#SR zXthlb9u^N@8Iyl&Qll5EKn74XoDtORYI^RP0|mfRYU0_U!MC`e#PxDm1=C4NY4xe1tpX_@7Ze>*z6n3SzvV=8pm0G09IL|yM^lvnB!2BAqID{yVE<^Fgr1FJk42X#!Y3fGL2}qN1XJmG^)7tu3JW1 zr!&rF1TsuB1#R|lFC}ft>W?|Of-_S`5mXU&%Kz1c!;~@bC;LbMsz9{9Aw4CVmccu< zqDV0S7O~k8f2UZkNuLHC=$)c8QMob5#(Q^OQixFT_WN zyh2v1KO3Jvq{|(RWyt7|SqtJxJ|BhhWJ##C4WMjR{OgzPyBFr*L=M*R9VgRV&@(ieKaAaTTcl3IQ$ltnNNp zV71GImM}9a9!5NOGM(>2$TF6FmPPqp z+?P?8Hr>QT{;I&)X+}=#EfBRwE4J@GPjz~|rS)~`9&dpGSGE{;`!OxP#hD(}K+vu% zuq7cepQsqO%1xO1?}@**B^l*1V>1|CrHX$NC3WPu;{^Oid!P+lxkNvW3 zcKCC$w-w&c!y^+n9}U8?1$tp^0$-k}5Fgo#9m=%18saE!#GMGIVhMM_bo*U=o`aa* zC$q{_I;8+D0g&XGyaV>HQ5dySPDh+kvH636cBpzAwVWcY&o})=H$PvHihQQOT{ykv z8{J(imAtT$z7w&Oc?AwMQ!cBg;y|Mq#&=O$TYvB8%6?``Iz815paF;dt4w|Qca-^G z|9mPkvYDw6a?l1pir;J6{~mqApH-ba2=e5?e)!>VEU+HDfsScM#ZLL)RH1}>PYa4J zle+eIafPJ0vs!M33`-%~%kb^Io8vyI>930aJlaG}MVm&Y_riY?53b$<`(%r2$j@Y= z(*%s)X;xQog!1(@Ek2yVbTwmO{3ps|$Z@<|3bG1FMNs z7+ut1TgZUK#%NtU29ESa;Nbc*km5)u3qDc z@mqSdn~pn4a>2e z>G{&O=teZzjPw4=8%OcLtJo~H+-D4E!rrflu^&CyY9WlZ76m`6pXR`udgzWR^j5-h z8{@ELYv}dq-jXf+sQAZnTrss54bI!X=YC}GwqW+}4?S+Lj8essdmS~KH4NHt-UpqZ z_CCXN+$NrZ5*fJnq#|0`NIUh8o&}s>iC8UqF(wzmhDWL*Lr})Zo>9@`Y+p_ZWsGJw z+FPOQWq^PUl2FxEmP ztp#^52S8jwEKb@6`kN%FlXM1av2pbmm|dOUI^Y(d;5e!_yVN|$PWY_@5kBB9w2RKj zqD`1~o-d_B25}jkH^|B~Vwj)L7F`>GU&$%T{n&0&uyyYPmdz5wJzM4APTa8EzC; z*1b;I&wd+O#lJ0-BDw~jij(trDfaj+7ORqSg+q)VW3&Jj*nmkDIx=m{d^O$|a?Y|s z=?x31H-6;_01^45D$+NG2%zR`ghVA_!rlXIbbU2Jv0?XCv;xSo)##A0xKPtA$5 zsoMVz%W)`4ivaB+@Z{fNWMz(Nwu~~Q%7^ey=-Mg4#~}*SZ2(mfKe|!0ZxUHjGJLv zTE+7h25^e?yW32&E6WMVX8kYz`j^gD$#`pq*m@Or*bK7U@u>Kg5_YZ^JEW^i8vx4$ z_cPc^(Cj5J^3n`q0 z7{_0(ETgr2t{Ji|yd7c9X|$uMr1!T*J4Skk?fNwA63$B^_DbT>H_UCy{O}i@f`BD* z1TKl)?EcB&ie$*n)ttEfWoHm`6S1hghzKFB&FK7v+u5>9TGQ)$CLK_znSTYFjA3f`(TZr|}J{-?^WSP+-qZzpLudYw@BOqV9 znsZKiNu~UnWWGLJ?`!#%7dwcA{KlR}DCc5w9)!P^@0htY+9)^eycc5`(HX`c!%-Bd zNS6LGeWEGR>FMv9&(N(0wgW~QufA;8UvS@DfL=?}E&Axf@hQ1LT<`A!luCiT!rbm7@!PP98dTdM-A z``k=S)XhgWs9wZ=bI&tQ+A)++v>W^`4~d-;>UnF{wz?NbbZrDg?J{^imTO{?YFfv^ z8xtag=5y7dkUk1_9mn_tZhQR4_?Tp}ywx`-wlA)`NgV#^>y$O%iRfV=J`-DmdD{)G z<6#6+ox-JEw_Q1TLLL+(vdk1&+v6hNTtqMLm7!#Ukmj#-iCEBVw)nf{dOCJ%#<|BO zXPI2ip|gVrQvku;r-8||79L@rl7r!!8vvTaJ~v06K)zr9h$21Sb~U2qk`$<0ny>T^-Q}4 z(|rVCY7qxzG}h}40S@#4}6U;pp`Y>)~3N=6Ru zMCi=oQ{*?SDf}p`LmejrDohv!A#PQ=0UQbEGiI8w?6n7tk$xn%3mV2^5xPmu-UsYw z$_WG_iIyqOUwlEJ^qQzr5{-R9w}efvhkN- zqs(}G7&kmGHbC$P(MG6o9Kf{k46*WOXvu+BS|eC;MU?A*2bpP3P+_UGm_MYv&?*(LQu5cPVMh*zqQr_?yMU@@L`_BWO_m{_D; zu5+iTu6&KNl6tt2!DBIoqFM+P?GQ55%{__@k3Q}umyW47|1k;Jf3#P7WILDk0BAsZ1GAO3kdUX;AbX2wp9vwj~!j z`g4XgFLxM@51Z*r9Q)rkz}tw&k_=y8CvKD&tqphn1mVLbm)Eqh)Es z`Yvn!smYtoRs0Z9`2Dgj6~Uic<|{#nOMYwT)IhqR`AXvDS?SX3Q^Hx_eCott4g-bp zCW`cNM|jRdwb5op5tYx}ratu?8Onk)IiZxi68A0lCm1z4Bb+s}KMb3JkeuZ$=9|dU>uBAN7FfXX zg>5>OX?jC!E+mW1dF7nCeI6Cf(h0ovax6Q&3<*dsQRTB$;lZieJK-JvRRB`tyU@a1 zx%mkr+sw!BHfnG%5ppfGT=3P zmVffbEg}B1AQ_ORVy}G6F>9_}*Io88TI*1j2^4@HeuP%8dQLG(k(l0%`&F#!;Bn^e z3|>TB9G%Y@#_JiSP-8xR2ZImkx${SfN^GY-bPoQA_}O}rcie=iK+;km8es+0D4YI) zkNA)CEE;2@_{zth`N5RtFllC(Wgy;ol>Gd#XoxSz6SD445inXUKdTZVO24e%%j^GB z+gS$H@qB4Gkl=0sE*9L~ouIk6yA!zh#a$BI-QC^Y<%Zy{!Gk*lcUbbDUV(`jTI{PORBvIDig^-jrQD*)n>TWc8Y8@QSDu<_LKW}&yA=AX;QiM`qi9VDJAoXT~&03dZ zYHBLNx0vKP=&C4659rw--b>Z zn&{RGYkK5n*xpNh_qo3*d(mwXIqhAUS}mjf$RpLeITD3Yzw~Y*(zg#Sc=n^0^Zl%z zB|nra^Cl{9hJZS|9Td zrd`R^KoutEf_@?GwBHFBqe{ZH43e83%s3v3NtmyT;G-ijvYIkMb0LjqYCh zUg4P4+RW&W;sB;|R1Yu#!y46Lk>{V@YIZ#flFx2)tjT5eb-bdiay z-0@`DUBczhxq3KZvqat7X~p}i-_I|JQ{e=C(H4Hu@dQ~_ zH=6uvWR^z8Lq|?{&1_{!xJ+5!17^*?1Y39xVIe+z6Y-j(drEIEs8jFF;7NZQJa?XL z${+}BS;DN#YtZ0VEm!7_r%u|18+Q40?BjIgB84&E^hN94?P;`o^9^aPzMu6L*9#E` zLNS3Fe)~&}T-w-#06{Uq6DlgS`+!EzXnX4kfEjA0bVrkr4S+uN;4KfTv za$yj!h~c^_DJyyNv28eGYt!e7RoIQz~o9XG0$TPO%zgi_>uBJX8- zIG${PmY4S+@9BMkOk8!H>Ncqw#)h+E;1;j(gvxTC*sRsy!%kn+Ib2gHsok}hJ?-Ol za{@cn{&eQW>%`jT;9rM2iimY2!wuid8V?PKifrw}98^zT$(>4~oALrMAu ztF9$rG^}!!tO6TlzLiYfyszExIKUKPT(}8wuWrUQ>OzI&Ou<_%h)n&d(UX z4}ia}#pO#RQ`NTGIM$Jvjm9JAGQ&RRzum@UZBR4aFx#T@s2;`;-45S2kPI6<)Q8MB zb!yr*Zu6z6aD|*t%%QKjz*xj&%^7@Lr%HcKeYuZrVhxM*?+8GY_|@GYz4B2Mj~f|1 zi!NYuQl{c1|6Vp(;)(jb_>turM86sX(AoK?Y(??v;V^)P&9lmGxu6=CTt@@9E6O8R z-69~-(Os!|1kQM_RTvW%9BP6D7iNZ|7w|d%BW&?S-q792ri(3t&F!awi#;yw4I)Ca zj*}}<@EP^tRSMl^b=s@at!L5c4hbg76FDP`)N$6797owPlXU|ixBe16G5rQJe*Rg1 zA1q5|I)i;~`~wlPC{5p>&XgzWpJjYel)!JJ_3;sXbAB2(pfWN34~hj{TNkg6wd?~s z#uYO!y|{vBW(j9)$i!5O67rSuYNERC9~1Pw=KD+pqnA-qt*GR<~Flbydkj!JF7-=M?x! z*pQ9oFgfJJgX}m}WQmaWWc0A;Xlf>=s9KW&q2mORMj+ms{m zRb^_ICl^LE%h70qFQ$!w{%B!dKaXmaxOZdVIf|)6Cj~I>D!G_Crl&759K_?@wm*c) z7ahTtKC4M+;(-a0&t`hig9<{o720%umKevuRLCwGtk6@VDqVd2&Y=N}qc{-WIY6Mm zMuV;B9{VPx4#lY^Mf3?gOI|J#+8`%PI&?LZUnP04zr-RuH~J){hX#x*D9-SrjC{K> z1rV*`7jfv_-CeL28qkAg+no^@r`i;TLb18INo>qXaj+4y*GK_WUZmrSiJ_IBju$UF z1-{Oc?8Q(3UE>`o{_){q$QJW<{#KLkLn5MYPU8yTZmufG&r3|H>#2QkrLY=iN$w!4 z)qj%yUK>yy62xrvOkIJ%!BrQ@{z`pDFLPq{>lh8s;IRv`a%HSD-`I@yhPQViYgurm zNFG9r{h4@eC_5lr>{?8W?B>cUW&8U0{I~YgzMn(C2T(f0vGS`7O0UX|Hic7mTR!;G zfG>|!?aqs}%gtR@uZNMbx+@KSltvI_Xw^rNoBjzq+#HD`_DquTT9b~>qmg(m@y4%{ z@Y#R!Sg5o)8ASJ6&CJ_AlM(^yYTp3i`bUYH{V3IFUdbsGQKclaao83W!x-F56+;k8 z7^95Gap}swfC;%8JHxj?B$?pJJpz*c3V<9IW6u6LLOe5d{2Mw&#sza-+_JrP0!P!X zxUx?e+@wcjbbCFCtbQLEihxf7G!*q7n1FfP7%=4g)J>!eJvcgy}e>H&~b=u3DadL~eXjPxQ_&LdKH1H`+oiKrb&ao-?0tr_7eKpnC=k68Teq2unHYnu36X7R1Nyx^Yt))np$UOsg6 z%~rPVuh3xttmVw6VH{AZ3PYr4&B28+88(3+cif9As@RriowXweg7tXe$sZ_eTWh(d zkN8hXNOb<>wk}jm#VPi7sxK?yc})ZSlSn!ey~E3>J7jOFUjj}}|^K7o{(Yg+1UXu0MU`5)l%OF@gc&9RmIFVXrwmJImk)&U*4X;TsxoK__UBm)j!9p^j$PX>#awh^`w2X|eb~ zA>6|P;N0BY|i4R|7IBI0|iEj!EUE8m)jwSRCSmmKdkk z**orI@nthPa|{e1QM9ry(+ zB2T;_o+ZM{Q6vKr=J?j1Bc+nY6-Nxdr{-~ENG727*s?M0F=R2UxhR@QBa}^Mj-w0a zersCD%Ijp1vBHr;6PAVvABk^QN{Y8IOX)40&sukqcfGc;YqVVbLS)`;Fsp7Y!d_x@ z@Kis0Vzy-D=H5CCbdPaA**omnL$cGhFlCkqQU=QLfyn@uVyR!)k|ZnRZ@Y7SYTEP5 z*{Q*b+(SxsqGN!}c;OJPM4sik5#L?L^R6v*>8 zZntc)+gm3?Gr|8F^W_x>k**Oj(CZ@nSrinG+mV06&ub0A}~=c-Dj% zO%un#tI&JTw`aaY#3mM`ZDL4Qw1l-1!D~(1l38e`MkgYYyZVK3bt0T#tHxtz~u^WZT#Tg-CbV=x!ho`UG0+`ma%6TuEXwk?g%8SCN4S&AD3 zZ;Lgn5UKJp;)jz~X)_Xz(^bE=Cc zO8D_5&_^YYV9`K zd!6=|f-xLjW6raEsN(~}g>Ojv7DIpQug5ZI;3vM>4vYL(QXAwp60VYcYVtuTX0x?3 z8{><@ZjHKEfjERt=o~0v7w(fZGK)2B3m$4q$59A=lqOtKgy|TrV6LjCApJ)COrPt6 z*BJK#=hOh`455umui+q(Z7;r8+oj{?oA~u*4jIXC12Ro|b>AP%S}r*wjzr_(1!;(G zOL}{E(SiRekF7bdC!0`XsxiL<(G#ho5+_uj3phrl_FV91bIs(_@Ev+P0oV=sSi;aN z{ft9?zgDf|bEBsc>R){%`tfYXVb03)pz=5e<^@C5#56gg`Y);e7?F=29}ev4C)bRp z`sT%Cn*ouDgtl**HaSvC{rGHFf2p0Tty5L&IQ~u>rro5nxu3FzRFK-{w{h-5>TagN z&ysP@KeaRYt`#E1t;JzJ%NDHCmi)2K0TN(I#nq9IoxK>Z+7s-S?$FIhFUb{xj`&Zy zSfXB;HS-p=E=*EC?3a1Diz(IVU?SJixd_e(#|zyXnv`?R{oTP};$(F>v#YBEFZ5?D zpsy3-PL|RAe$_1fS;QN{WxCQ#jPZt*_O%I&JGljO7P?>Va)8$&+Hj7QN>@wg8{B)( z(l|d2+I?GOZu&I44r7&xYPCRzyq+S~pNEQ9p>MdDo$qBP@2iUDKViuAx)>TOr98^h z##s^2UWp?Qb?tt>Wm7P;@zzY;FUoePD1<9gLN^2{Gt@BI;Iq`MoYX@i)H9~U4T3}tC zD}{E&yAGEEzFSore-5tYNO4h`M%i4D@>{sbyTK`@&u~4zEj=EYYYb|yi zqdXntH!4SNzU<7qvzFF>%RXZ7xGcLy_)Pe`8eP}X+$@{;7OaIjyslg9B2iG_V}x;z z^;d)TviviEojsf5O_a8lK)LNFMyNEqAm;V)(`Ra6D?m)RdU`dkuQ5B7#gtm>*Od7& zs&bXVhO{K?-kyY^74HOuHQQc5qgQZKC90q>-h$%vp9-`Pfy>b1b zTCesFXWoUY#1XCT@r#h?cHL#CB_1|Rq9^u9m1a-IXzN$@dnwm?VV!RWA7%)a^Jx%K zD|cfIVP*Q=$3fficH2CQ&<%}Q`7)I6b40=5O~9GQRdwMQnP@ z2!0VEXp?DPCY(9NFk*jHMYZ37rzn&3RPsOj?5IrG=}p)%(nQ)^s-sUy2-0{uy{R=A zb1G+oxph2oK8S1U93!J?;v!rq*!|ID;#R-vUmpI}YuIDBBbUv|o5Ey3q1Kd60aQqN zBw12Cws;{!d zxdfK@z{YBcz8hN}RZJQe;xI}382g2Y{L5z&p7*$#fu0F*jFBnQmMNA4LFp1iMqC)pS z%{t)&6t@;US*_Mk+mE1CkZlu^>k}#87+;{rPqi7?URLPxYQbC5@Ed9XWbfH z1ypm_i0QTiwT3T7WRkNz`mFKZc3`(WkR7=1+(?l|2cGp;LT+Q#9&C zTn?NA$yMNP$rOLY3w9n~eCQ`m_{X$>LmV#rnZX9%B%?EKh}`?#3JNB?XZRYGc(roa zo3i+?#|EQ&ItFHzj>T*??T4IVwJP!sJ21kf@pbC~!p` zkk}4~x@+?$rYpp5Nu<#QXw207`GXH1L8eLN`z7uwp#61EdP`k$?gH|YJthW#a=>E4 z>@ND51U&?dprBJkKI7iM4s&~<24B7qG*!!8Lj!<@9?9(wD`IXK(4%Z=G-6Q`c!oFU z51$GASfzOHw6`ksd0!kheXTUGJsvKr3bkcEdN&9De@;_SYW#1QebD>(OrMX-9YQkm zfrOe{K<}j1rA&MlB0l=fyKgz7#0svTeAIj=xE;(3h+38^P5w%gdqPOIzERoM6yq79 zg#pFW?zVYq7})7+RYXE3K^umJ;qQT&^ARsn61x~4_J+aWIQSTy)sNe9QRLL8h~pA6 zw2H+IC*`-c60xy9zk^WtKNJ0#(*KF*NAIIlD|Wx{NJDoM$w2l2l6`*y8N7>O0ob}( z**}K0yv?xw zy)kq&BJx37VLauwu~`=Vt$A<{gntg(Vk*n?59T=FxmRtbXB;OzR0}`n5Vb-p5?XMY zAQ70MgMOGsG^D+2^uCq= zAS@#_7s{7~lpBS-lacUN)mgqxI*q)pCCFWn!=&yT!g@F)94re*9so0V-!x<1_kR`Q z4Y5A5J;cyrg?QbspJIWQO~*@r71t~VQ@k%FrF@6)-1CQRqoWCIW)!}#d0&*2ll~J( zjH$E&zP**B0Gj6iYijU=)I;$<2FeygyqIr>Z-CB%|K-cyqpO~;pZ@VX{r>S)k12_0 UB2BC3@6Q5&67u3zqK1C|23O7vasU7T literal 0 HcmV?d00001 diff --git a/localization/ndt_scan_matcher/src/diagnostics_module.cpp b/localization/ndt_scan_matcher/src/diagnostics_module.cpp new file mode 100644 index 0000000000000..9d7eed46414ea --- /dev/null +++ b/localization/ndt_scan_matcher/src/diagnostics_module.cpp @@ -0,0 +1,104 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ndt_scan_matcher/diagnostics_module.hpp" + +#include + +#include + +#include +#include + +DiagnosticsModule::DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name) +: clock_(node->get_clock()) +{ + diagnostics_pub_ = + node->create_publisher("/diagnostics", 10); + + diagnostics_status_msg_.name = + std::string(node->get_name()) + std::string(": ") + diagnostic_name; + diagnostics_status_msg_.hardware_id = node->get_name(); +} + +void DiagnosticsModule::clear() +{ + diagnostics_status_msg_.values.clear(); + diagnostics_status_msg_.values.shrink_to_fit(); + + diagnostics_status_msg_.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + diagnostics_status_msg_.message = ""; +} + +void DiagnosticsModule::addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg) +{ + auto it = std::find_if( + std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values), + [key_value_msg](const auto & arg) { return arg.key == key_value_msg.key; }); + + if (it != std::cend(diagnostics_status_msg_.values)) { + it->value = key_value_msg.value; + } else { + diagnostics_status_msg_.values.push_back(key_value_msg); + } +} + +template <> +void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value) +{ + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = key; + key_value.value = value; + addKeyValue(key_value); +} + +template <> +void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value) +{ + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = key; + key_value.value = value ? "True" : "False"; + addKeyValue(key_value); +} + +void DiagnosticsModule::updateLevelAndMessage(const int8_t level, const std::string & message) +{ + if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) { + if (!diagnostics_status_msg_.message.empty()) { + diagnostics_status_msg_.message += "; "; + } + diagnostics_status_msg_.message += message; + } + if (level > diagnostics_status_msg_.level) { + diagnostics_status_msg_.level = level; + } +} + +void DiagnosticsModule::publish() +{ + diagnostics_pub_->publish(createDiagnosticsArray()); +} + +diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::createDiagnosticsArray() const +{ + diagnostic_msgs::msg::DiagnosticArray diagnostics_msg; + diagnostics_msg.header.stamp = clock_->now(); + diagnostics_msg.status.push_back(diagnostics_status_msg_); + + if (diagnostics_msg.status.at(0).level == diagnostic_msgs::msg::DiagnosticStatus::OK) { + diagnostics_msg.status.at(0).message = "OK"; + } + + return diagnostics_msg; +} diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index ca56a93cec859..43174a39b797e 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -34,7 +34,10 @@ MapUpdateModule::MapUpdateModule( if (ndt_ptr_) { *secondary_ndt_ptr_ = *ndt_ptr_; } else { - RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "Attempt to update a null NDT pointer."); + std::stringstream message; + message << "Error at MapUpdateModule::MapUpdateModule." + << "`ndt_ptr_` is a null NDT pointer."; + throw std::runtime_error(message.str()); } // Initially, a direct map update on ndt_ptr_ is needed. @@ -45,7 +48,41 @@ MapUpdateModule::MapUpdateModule( need_rebuild_ = true; } -bool MapUpdateModule::should_update_map(const geometry_msgs::msg::Point & position) +void MapUpdateModule::callback_timer( + const bool is_activated, const std::optional & position, + std::unique_ptr & diagnostics_ptr) +{ + diagnostics_ptr->addKeyValue("timer_callback_time_stamp", clock_->now().seconds()); + + // check is_activated + diagnostics_ptr->addKeyValue("is_activated", is_activated); + if (!is_activated) { + std::stringstream message; + message << "Node is not activated."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return; + } + + // check is_set_last_update_position + const bool is_set_last_update_position = (position != std::nullopt); + diagnostics_ptr->addKeyValue("is_set_last_update_position", is_set_last_update_position); + if (!is_set_last_update_position) { + std::stringstream message; + message << "Cannot find the reference position for map update." + << "Please check if the EKF odometry is provided to NDT."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return; + } + + if (should_update_map(position.value(), diagnostics_ptr)) { + update_map(position.value(), diagnostics_ptr); + } +} + +bool MapUpdateModule::should_update_map( + const geometry_msgs::msg::Point & position, std::unique_ptr & diagnostics_ptr) { if (last_update_position_ == std::nullopt) { need_rebuild_ = true; @@ -55,8 +92,15 @@ bool MapUpdateModule::should_update_map(const geometry_msgs::msg::Point & positi const double dx = position.x - last_update_position_.value().x; const double dy = position.y - last_update_position_.value().y; const double distance = std::hypot(dx, dy); + + // check distance_last_update_position_to_current_position + diagnostics_ptr->addKeyValue("distance_last_update_position_to_current_position", distance); if (distance + param_.lidar_radius > param_.map_radius) { - RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "Dynamic map loading is not keeping up."); + std::stringstream message; + message << "Dynamic map loading is not keeping up."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + // If the map does not keep up with the current position, // lock ndt_ptr_ entirely until it is fully rebuilt. need_rebuild_ = true; @@ -65,8 +109,11 @@ bool MapUpdateModule::should_update_map(const geometry_msgs::msg::Point & positi return distance > param_.update_distance; } -void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position) +void MapUpdateModule::update_map( + const geometry_msgs::msg::Point & position, std::unique_ptr & diagnostics_ptr) { + diagnostics_ptr->addKeyValue("is_need_rebuild", need_rebuild_); + // If the current position is super far from the previous loading position, // lock and rebuild ndt_ptr_ if (need_rebuild_) { @@ -82,25 +129,37 @@ void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position) ndt_ptr_->setInputSource(input_source); } - const bool updated = update_ndt(position, *ndt_ptr_); + const bool updated = update_ndt(position, *ndt_ptr_, diagnostics_ptr); + + // check is_updated_map + diagnostics_ptr->addKeyValue("is_updated_map", updated); if (!updated) { - RCLCPP_ERROR_STREAM_THROTTLE( - logger_, *clock_, 1000, - "update_ndt failed. If this happens with initial position estimation, make sure that" - "(1) the initial position matches the pcd map and (2) the map_loader is working properly."); + std::stringstream message; + message + << "update_ndt failed. If this happens with initial position estimation, make sure that" + << "(1) the initial position matches the pcd map and (2) the map_loader is working " + "properly."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, message.str()); last_update_position_ = position; ndt_ptr_mutex_->unlock(); return; } + ndt_ptr_mutex_->unlock(); need_rebuild_ = false; + } else { // Load map to the secondary_ndt_ptr, which does not require a mutex lock // Since the update of the secondary ndt ptr and the NDT align (done on // the main ndt_ptr_) overlap, the latency of updating/alignment reduces partly. // If the updating is done the main ndt_ptr_, either the update or the NDT // align will be blocked by the other. - const bool updated = update_ndt(position, *secondary_ndt_ptr_); + const bool updated = update_ndt(position, *secondary_ndt_ptr_, diagnostics_ptr); + + // check is_updated_map + diagnostics_ptr->addKeyValue("is_updated_map", updated); if (!updated) { last_update_position_ = position; return; @@ -128,8 +187,12 @@ void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position) publish_partial_pcd_map(); } -bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, NdtType & ndt) +bool MapUpdateModule::update_ndt( + const geometry_msgs::msg::Point & position, NdtType & ndt, + std::unique_ptr & diagnostics_ptr) { + diagnostics_ptr->addKeyValue("maps_size_before", ndt.getCurrentMapIDs().size()); + auto request = std::make_shared(); request->area.center_x = static_cast(position.x); @@ -138,7 +201,13 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt request->cached_ids = ndt.getCurrentMapIDs(); while (!pcd_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) { - RCLCPP_INFO(logger_, "Waiting for pcd loader service. Check the pointcloud_map_loader."); + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", false); + + std::stringstream message; + message << "Waiting for pcd loader service. Check the pointcloud_map_loader."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; } // send a request to map_loader @@ -148,20 +217,27 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt std::future_status status = result.wait_for(std::chrono::seconds(0)); while (status != std::future_status::ready) { - RCLCPP_INFO(logger_, "waiting response"); + // check is_succeed_call_pcd_loader if (!rclcpp::ok()) { + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", false); + + std::stringstream message; + message << "pcd_loader service is not working."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; // No update } status = result.wait_for(std::chrono::seconds(1)); } + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", true); auto & maps_to_add = result.get()->new_pointcloud_with_ids; auto & map_ids_to_remove = result.get()->ids_to_remove; - RCLCPP_INFO( - logger_, "Update map (Add: %lu, Remove: %lu)", maps_to_add.size(), map_ids_to_remove.size()); + diagnostics_ptr->addKeyValue("maps_to_add_size", maps_to_add.size()); + diagnostics_ptr->addKeyValue("maps_to_remove_size", map_ids_to_remove.size()); + if (maps_to_add.empty() && map_ids_to_remove.empty()) { - RCLCPP_INFO(logger_, "Skip map update"); return false; // No update } @@ -187,7 +263,9 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt const auto duration_micro_sec = std::chrono::duration_cast(exe_end_time - exe_start_time).count(); const auto exe_time = static_cast(duration_micro_sec) / 1000.0; - RCLCPP_DEBUG(logger_, "Time duration for creating new ndt_ptr: %lf [ms]", exe_time); + diagnostics_ptr->addKeyValue("map_update_execution_time", exe_time); + diagnostics_ptr->addKeyValue("maps_size_after", ndt.getCurrentMapIDs().size()); + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", true); return true; // Updated } diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index ba4190d9f66fb..1e3188a15acc9 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -70,12 +70,9 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) tf2_buffer_(this->get_clock()), tf2_listener_(tf2_buffer_), ndt_ptr_(new NormalDistributionsTransform), - state_ptr_(new std::map), is_activated_(false), param_(this) { - (*state_ptr_)["state"] = "Initializing"; - timer_callback_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); rclcpp::CallbackGroup::SharedPtr initial_pose_callback_group = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); @@ -117,6 +114,9 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) const double value_as_unlimited = 1000.0; regularization_pose_buffer_ = std::make_unique(this->get_logger(), value_as_unlimited, value_as_unlimited); + + diagnostics_regularization_pose_ = + std::make_unique(this, "regularization_pose_subscriber_status"); } sensor_aligned_pose_pub_ = @@ -158,8 +158,6 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) this->create_publisher( "initial_to_result_distance_new", 10); ndt_marker_pub_ = this->create_publisher("ndt_marker", 10); - diagnostics_pub_ = - this->create_publisher("/diagnostics", 10); ndt_monte_carlo_initial_pose_marker_pub_ = this->create_publisher( "monte_carlo_initial_pose_marker", 10); @@ -184,112 +182,68 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) map_update_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_, param_.dynamic_map_loading); + diagnostics_scan_points_ = std::make_unique(this, "scan_matching_status"); + diagnostics_initial_pose_ = + std::make_unique(this, "initial_pose_subscriber_status"); + diagnostics_map_update_ = std::make_unique(this, "map_update_status"); + diagnostics_ndt_align_ = std::make_unique(this, "ndt_align_service_status"); + diagnostics_trigger_node_ = + std::make_unique(this, "trigger_node_service_status"); + logger_configure_ = std::make_unique(this); } -void NDTScanMatcher::publish_diagnostic() +void NDTScanMatcher::callback_timer() { - diagnostic_msgs::msg::DiagnosticStatus diag_status_msg; - diag_status_msg.name = "ndt_scan_matcher"; - diag_status_msg.hardware_id = ""; - - for (const auto & key_value : (*state_ptr_)) { - diagnostic_msgs::msg::KeyValue key_value_msg; - key_value_msg.key = key_value.first; - key_value_msg.value = key_value.second; - diag_status_msg.values.push_back(key_value_msg); - } - - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - diag_status_msg.message = ""; - if (state_ptr_->count("state") && (*state_ptr_)["state"] == "Initializing") { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "Initializing State. "; - } - if ( - state_ptr_->count("lidar_topic_delay_time_sec") && - std::stod((*state_ptr_)["lidar_topic_delay_time_sec"]) > - param_.validation.lidar_topic_timeout_sec) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "lidar_topic_delay_time_sec exceed limit. "; - } - if ( - state_ptr_->count("skipping_publish_num") && - std::stoi((*state_ptr_)["skipping_publish_num"]) > 1 && - std::stoi((*state_ptr_)["skipping_publish_num"]) < 5) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "skipping_publish_num > 1. "; - } - if ( - state_ptr_->count("skipping_publish_num") && - std::stoi((*state_ptr_)["skipping_publish_num"]) >= 5) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - diag_status_msg.message += "skipping_publish_num exceed limit. "; - } - if ( - state_ptr_->count("nearest_voxel_transformation_likelihood") && - std::stod((*state_ptr_)["nearest_voxel_transformation_likelihood"]) < - param_.score_estimation.converged_param_nearest_voxel_transformation_likelihood) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "NDT score is unreliably low. "; - } - if ( - state_ptr_->count("execution_time") && std::stod((*state_ptr_)["execution_time"]) >= - param_.validation.critical_upper_bound_exe_time_ms) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += - "NDT exe time is too long. (took " + (*state_ptr_)["execution_time"] + " [ms])"; - } - // Ignore local optimal solution - if ( - state_ptr_->count("is_local_optimal_solution_oscillation") && - std::stoi((*state_ptr_)["is_local_optimal_solution_oscillation"])) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - diag_status_msg.message = "local optimal solution oscillation occurred"; - } - - diagnostic_msgs::msg::DiagnosticArray diag_msg; - diag_msg.header.stamp = this->now(); - diag_msg.status.push_back(diag_status_msg); - - diagnostics_pub_->publish(diag_msg); + diagnostics_map_update_->clear(); + + map_update_module_->callback_timer(is_activated_, latest_ekf_position_, diagnostics_map_update_); + + diagnostics_map_update_->publish(); } -void NDTScanMatcher::callback_timer() +void NDTScanMatcher::callback_initial_pose( + const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr) { - if (!is_activated_) { - return; - } - std::lock_guard lock(latest_ekf_position_mtx_); - if (latest_ekf_position_ == std::nullopt) { - RCLCPP_ERROR_STREAM_THROTTLE( - this->get_logger(), *this->get_clock(), 1000, - "Cannot find the reference position for map update. Please check if the EKF odometry is " - "provided to NDT."); - return; - } - // continue only if we should update the map - if (map_update_module_->should_update_map(latest_ekf_position_.value())) { - RCLCPP_INFO(this->get_logger(), "Start updating NDT map (timer_callback)"); - map_update_module_->update_map(latest_ekf_position_.value()); - } + diagnostics_initial_pose_->clear(); + + callback_initial_pose_main(initial_pose_msg_ptr); + + diagnostics_initial_pose_->publish(); } -void NDTScanMatcher::callback_initial_pose( +void NDTScanMatcher::callback_initial_pose_main( const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr) { - if (!is_activated_) return; + diagnostics_initial_pose_->addKeyValue( + "topic_time_stamp", static_cast(initial_pose_msg_ptr->header.stamp).seconds()); - if (initial_pose_msg_ptr->header.frame_id == param_.frame.map_frame) { - initial_pose_buffer_->push_back(initial_pose_msg_ptr); - } else { - RCLCPP_ERROR_STREAM_THROTTLE( - get_logger(), *this->get_clock(), 1000, - "Received initial pose message with frame_id " - << initial_pose_msg_ptr->header.frame_id << ", but expected " << param_.frame.map_frame - << ". Please check the frame_id in the input topic and ensure it is correct."); + // check is_activated + diagnostics_initial_pose_->addKeyValue("is_activated", static_cast(is_activated_)); + if (!is_activated_) { + std::stringstream message; + message << "Node is not activated."; + diagnostics_initial_pose_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return; } + // check is_expected_frame_id + const bool is_expected_frame_id = + (initial_pose_msg_ptr->header.frame_id == param_.frame.map_frame); + diagnostics_initial_pose_->addKeyValue("is_expected_frame_id", is_expected_frame_id); + if (!is_expected_frame_id) { + std::stringstream message; + message << "Received initial pose message with frame_id " + << initial_pose_msg_ptr->header.frame_id << ", but expected " << param_.frame.map_frame + << ". Please check the frame_id in the input topic and ensure it is correct."; + diagnostics_initial_pose_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + return; + } + + initial_pose_buffer_->push_back(initial_pose_msg_ptr); + { // latest_ekf_position_ is also used by callback_timer, so it is necessary to acquire the lock std::lock_guard lock(latest_ekf_position_mtx_); @@ -300,41 +254,82 @@ void NDTScanMatcher::callback_initial_pose( void NDTScanMatcher::callback_regularization_pose( geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose_conv_msg_ptr) { + diagnostics_regularization_pose_->clear(); + + diagnostics_regularization_pose_->addKeyValue( + "topic_time_stamp", static_cast(pose_conv_msg_ptr->header.stamp).seconds()); + regularization_pose_buffer_->push_back(pose_conv_msg_ptr); + + diagnostics_regularization_pose_->publish(); } void NDTScanMatcher::callback_sensor_points( sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame) { - if (sensor_points_msg_in_sensor_frame->data.empty()) { - RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "Empty sensor points!"); - return; + // clear diagnostics + diagnostics_scan_points_->clear(); + + // scan matching + const bool is_succeed_scan_matching = + callback_sensor_points_main(sensor_points_msg_in_sensor_frame); + + // check skipping_publish_num + static size_t skipping_publish_num = 0; + const size_t error_skipping_publish_num = 5; + skipping_publish_num = is_succeed_scan_matching ? 0 : (skipping_publish_num + 1); + diagnostics_scan_points_->addKeyValue("skipping_publish_num", skipping_publish_num); + if (skipping_publish_num >= error_skipping_publish_num) { + std::stringstream message; + message << "skipping_publish_num exceed limit (" << skipping_publish_num << " times)."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); } + diagnostics_scan_points_->publish(); +} + +bool NDTScanMatcher::callback_sensor_points_main( + sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame) +{ + const auto exe_start_time = std::chrono::system_clock::now(); + + // check topic_time_stamp const rclcpp::Time sensor_ros_time = sensor_points_msg_in_sensor_frame->header.stamp; - const double lidar_topic_delay_time_sec = (this->now() - sensor_ros_time).seconds(); - (*state_ptr_)["lidar_topic_delay_time_sec"] = std::to_string(lidar_topic_delay_time_sec); + diagnostics_scan_points_->addKeyValue("topic_time_stamp", sensor_ros_time.seconds()); + + // check sensor_points_size + const size_t sensor_points_size = sensor_points_msg_in_sensor_frame->width; + diagnostics_scan_points_->addKeyValue("sensor_points_size", sensor_points_size); + if (sensor_points_size == 0) { + std::stringstream message; + message << "Sensor points is empty."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; + } - if (lidar_topic_delay_time_sec > param_.validation.lidar_topic_timeout_sec) { - RCLCPP_WARN( - this->get_logger(), - "The LiDAR topic is experiencing latency. The delay time is %lf[sec] (the tolerance is " - "%lf[sec])", - lidar_topic_delay_time_sec, param_.validation.lidar_topic_timeout_sec); + // check sensor_points_delay_time_sec + const double sensor_points_delay_time_sec = + (this->now() - sensor_points_msg_in_sensor_frame->header.stamp).seconds(); + diagnostics_scan_points_->addKeyValue( + "sensor_points_delay_time_sec", sensor_points_delay_time_sec); + if (sensor_points_delay_time_sec > param_.validation.lidar_topic_timeout_sec) { + std::stringstream message; + message << "sensor points is experiencing latency." + << "The delay time is " << sensor_points_delay_time_sec << "[sec] " + << "(the tolerance is " << param_.validation.lidar_topic_timeout_sec << "[sec])."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); // If the delay time of the LiDAR topic exceeds the delay compensation time of ekf_localizer, // even if further processing continues, the estimated result will be rejected by ekf_localizer. // Therefore, it would be acceptable to exit the function here. // However, for now, we will continue the processing as it is. - // return; + // return false; } - // mutex ndt_ptr_ - std::lock_guard lock(ndt_ptr_mtx_); - - const auto exe_start_time = std::chrono::system_clock::now(); - // preprocess input pointcloud pcl::shared_ptr> sensor_points_in_sensor_frame( new pcl::PointCloud); @@ -343,34 +338,73 @@ void NDTScanMatcher::callback_sensor_points( const std::string & sensor_frame = sensor_points_msg_in_sensor_frame->header.frame_id; pcl::fromROSMsg(*sensor_points_msg_in_sensor_frame, *sensor_points_in_sensor_frame); - transform_sensor_measurement( - sensor_frame, param_.frame.base_frame, sensor_points_in_sensor_frame, - sensor_points_in_baselink_frame); - // check max distance of sensor points + // transform sensor points from sensor-frame to base_link + try { + transform_sensor_measurement( + sensor_frame, param_.frame.base_frame, sensor_points_in_sensor_frame, + sensor_points_in_baselink_frame); + } catch (const std::exception & ex) { + std::stringstream message; + message << ex.what() << ". Please publish TF " << sensor_frame << " to " + << param_.frame.base_frame; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); + diagnostics_scan_points_->addKeyValue("is_succeed_transform_sensor_points", false); + return false; + } + diagnostics_scan_points_->addKeyValue("is_succeed_transform_sensor_points", true); + + // check sensor_points_max_distance double max_distance = 0.0; for (const auto & point : sensor_points_in_baselink_frame->points) { const double distance = std::hypot(point.x, point.y, point.z); max_distance = std::max(max_distance, distance); } + + diagnostics_scan_points_->addKeyValue("sensor_points_max_distance", max_distance); if (max_distance < param_.sensor_points.required_distance) { - RCLCPP_WARN_STREAM( - this->get_logger(), "Max distance of sensor points = " - << std::fixed << std::setprecision(3) << max_distance << " [m] < " - << param_.sensor_points.required_distance << " [m]"); - return; + std::stringstream message; + message << "Max distance of sensor points = " << std::fixed << std::setprecision(3) + << max_distance << " [m] < " << param_.sensor_points.required_distance << " [m]"; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; } + // lock mutex + std::lock_guard lock(ndt_ptr_mtx_); + + // set sensor points to ndt class ndt_ptr_->setInputSource(sensor_points_in_baselink_frame); - if (!is_activated_) return; + + // check is_activated + diagnostics_scan_points_->addKeyValue("is_activated", static_cast(is_activated_)); + if (!is_activated_) { + std::stringstream message; + message << "Node is not activated."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; + } // calculate initial pose std::optional interpolation_result_opt = initial_pose_buffer_->interpolate(sensor_ros_time); - if (!interpolation_result_opt) { - RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "No interpolated pose!"); - return; + + // check is_succeed_interpolate_initial_pose + const bool is_succeed_interpolate_initial_pose = (interpolation_result_opt != std::nullopt); + diagnostics_scan_points_->addKeyValue( + "is_succeed_interpolate_initial_pose", is_succeed_interpolate_initial_pose); + if (!is_succeed_interpolate_initial_pose) { + std::stringstream message; + message << "Couldn't interpolate pose. Please check the initial pose topic"; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; } + initial_pose_buffer_->pop_old(sensor_ros_time); const SmartPoseBuffer::InterpolateResult & interpolation_result = interpolation_result_opt.value(); @@ -380,9 +414,15 @@ void NDTScanMatcher::callback_sensor_points( add_regularization_pose(sensor_ros_time); } - if (ndt_ptr_->getInputTarget() == nullptr) { - RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "No MAP!"); - return; + // check is_set_map_points + const bool is_set_map_points = (ndt_ptr_->getInputTarget() != nullptr); + diagnostics_scan_points_->addKeyValue("is_set_map_points", is_set_map_points); + if (!is_set_map_points) { + std::stringstream message; + message << "Map points is not set."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; } // perform ndt scan matching @@ -399,26 +439,68 @@ void NDTScanMatcher::callback_sensor_points( transformation_msg_array.push_back(pose_ros); } - // perform several validations - bool is_ok_iteration_num = - validate_num_iteration(ndt_result.iteration_num, ndt_ptr_->getMaximumIterations()); - const int oscillation_num = count_oscillation(transformation_msg_array); - bool is_local_optimal_solution_oscillation = false; + // check iteration_num + diagnostics_scan_points_->addKeyValue("iteration_num", ndt_result.iteration_num); + const bool is_ok_iteration_num = (ndt_result.iteration_num < ndt_ptr_->getMaximumIterations()); if (!is_ok_iteration_num) { - constexpr int oscillation_threshold = 10; - is_local_optimal_solution_oscillation = (oscillation_num > oscillation_threshold); + std::stringstream message; + message << "The number of iterations has reached its upper limit. The number of iterations: " + << ndt_result.iteration_num << ", Limit: " << ndt_ptr_->getMaximumIterations() << "."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } - bool is_ok_converged_param = validate_converged_param( - ndt_result.transform_probability, ndt_result.nearest_voxel_transformation_likelihood); - bool is_converged = is_ok_iteration_num && is_ok_converged_param; - static size_t skipping_publish_num = 0; - if (is_converged) { - skipping_publish_num = 0; + + // check local_optimal_solution_oscillation_num + constexpr int oscillation_num_threshold = 10; + const int oscillation_num = count_oscillation(transformation_msg_array); + diagnostics_scan_points_->addKeyValue("local_optimal_solution_oscillation_num", oscillation_num); + const bool is_local_optimal_solution_oscillation = (oscillation_num > oscillation_num_threshold); + if (is_local_optimal_solution_oscillation) { + std::stringstream message; + message << "There is a possibility of oscillation in a local minimum"; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + } + + // check score + diagnostics_scan_points_->addKeyValue("transform_probability", ndt_result.transform_probability); + diagnostics_scan_points_->addKeyValue( + "nearest_voxel_transformation_likelihood", ndt_result.nearest_voxel_transformation_likelihood); + std::string score_name = ""; + double score = 0.0; + double score_threshold = 0.0; + if (param_.score_estimation.converged_param_type == ConvergedParamType::TRANSFORM_PROBABILITY) { + score_name = "Transform Probability"; + score = ndt_result.transform_probability; + score_threshold = param_.score_estimation.converged_param_transform_probability; + } else if ( + param_.score_estimation.converged_param_type == + ConvergedParamType::NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD) { + score_name = "Nearest Voxel Transformation Likelihood"; + score = ndt_result.nearest_voxel_transformation_likelihood; + score_threshold = + param_.score_estimation.converged_param_nearest_voxel_transformation_likelihood; } else { - ++skipping_publish_num; - RCLCPP_WARN(get_logger(), "Not Converged"); + std::stringstream message; + message << "Unknown converged param type. Please check `score_estimation.converged_param_type`"; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + return false; + } + + bool is_ok_score = (score > score_threshold); + if (!is_ok_score) { + std::stringstream message; + message << "Score is below the threshold. Score: " << score + << ", Threshold: " << score_threshold; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + RCLCPP_WARN_STREAM(this->get_logger(), message.str()); } + // check is_converged + bool is_converged = (is_ok_iteration_num || is_local_optimal_solution_oscillation) && is_ok_score; + // covariance estimation const Eigen::Quaterniond map_to_base_link_quat = Eigen::Quaterniond( result_pose_msg.orientation.w, result_pose_msg.orientation.x, result_pose_msg.orientation.y, @@ -435,10 +517,31 @@ void NDTScanMatcher::callback_sensor_points( ndt_covariance = estimated_covariance; } + // check distance_initial_to_result + const auto distance_initial_to_result = static_cast( + norm(interpolation_result.interpolated_pose.pose.pose.position, result_pose_msg.position)); + diagnostics_scan_points_->addKeyValue("distance_initial_to_result", distance_initial_to_result); + const double warn_distance_initial_to_result = 3.0; + if (distance_initial_to_result > warn_distance_initial_to_result) { + std::stringstream message; + message << "distance_initial_to_result is too large (" << distance_initial_to_result + << " [m])."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + } + + // check execution_time const auto exe_end_time = std::chrono::system_clock::now(); const auto duration_micro_sec = std::chrono::duration_cast(exe_end_time - exe_start_time).count(); const auto exe_time = static_cast(duration_micro_sec) / 1000.0f; + diagnostics_scan_points_->addKeyValue("execution_time", exe_time); + if (exe_time > param_.validation.critical_upper_bound_exe_time_ms) { + std::stringstream message; + message << "NDT exe time is too long (took " << exe_time << " [ms])."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + } // publish initial_pose_with_covariance_pub_->publish(interpolation_result.interpolated_pose); @@ -492,18 +595,7 @@ void NDTScanMatcher::callback_sensor_points( make_float32_stamped(sensor_ros_time, no_ground_nearest_voxel_transformation_likelihood)); } - (*state_ptr_)["state"] = "Aligned"; - (*state_ptr_)["transform_probability"] = std::to_string(ndt_result.transform_probability); - (*state_ptr_)["nearest_voxel_transformation_likelihood"] = - std::to_string(ndt_result.nearest_voxel_transformation_likelihood); - (*state_ptr_)["iteration_num"] = std::to_string(ndt_result.iteration_num); - (*state_ptr_)["skipping_publish_num"] = std::to_string(skipping_publish_num); - (*state_ptr_)["oscillation_count"] = std::to_string(oscillation_num); - (*state_ptr_)["is_local_optimal_solution_oscillation"] = - std::to_string(is_local_optimal_solution_oscillation); - (*state_ptr_)["execution_time"] = std::to_string(exe_time); - - publish_diagnostic(); + return is_converged; } void NDTScanMatcher::transform_sensor_measurement( @@ -520,12 +612,7 @@ void NDTScanMatcher::transform_sensor_measurement( try { transform = tf2_buffer_.lookupTransform(target_frame, source_frame, tf2::TimePointZero); } catch (tf2::TransformException & ex) { - RCLCPP_WARN(this->get_logger(), "%s", ex.what()); - RCLCPP_WARN( - this->get_logger(), "Please publish TF %s to %s", target_frame.c_str(), source_frame.c_str()); - // Since there is no clear error handling policy, temporarily return as is. - sensor_points_output_ptr = sensor_points_input_ptr; - return; + throw; } const geometry_msgs::msg::PoseStamped target_to_source_pose_stamped = @@ -638,54 +725,6 @@ void NDTScanMatcher::publish_initial_to_result( make_float32_stamped(sensor_ros_time, initial_to_result_distance_new)); } -bool NDTScanMatcher::validate_num_iteration(const int iter_num, const int max_iter_num) -{ - bool is_ok_iter_num = iter_num < max_iter_num; - if (!is_ok_iter_num) { - RCLCPP_WARN( - get_logger(), - "The number of iterations has reached its upper limit. The number of iterations: %d, Limit: " - "%d", - iter_num, max_iter_num); - } - return is_ok_iter_num; -} - -bool NDTScanMatcher::validate_score( - const double score, const double score_threshold, const std::string & score_name) -{ - bool is_ok_score = score > score_threshold; - if (!is_ok_score) { - RCLCPP_WARN( - get_logger(), "%s is below the threshold. Score: %lf, Threshold: %lf", score_name.c_str(), - score, score_threshold); - } - return is_ok_score; -} - -bool NDTScanMatcher::validate_converged_param( - const double & transform_probability, const double & nearest_voxel_transformation_likelihood) -{ - bool is_ok_converged_param = false; - if (param_.score_estimation.converged_param_type == ConvergedParamType::TRANSFORM_PROBABILITY) { - is_ok_converged_param = validate_score( - transform_probability, param_.score_estimation.converged_param_transform_probability, - "Transform Probability"); - } else if ( - param_.score_estimation.converged_param_type == - ConvergedParamType::NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD) { - is_ok_converged_param = validate_score( - nearest_voxel_transformation_likelihood, - param_.score_estimation.converged_param_nearest_voxel_transformation_likelihood, - "Nearest Voxel Transformation Likelihood"); - } else { - is_ok_converged_param = false; - RCLCPP_ERROR_STREAM_THROTTLE( - this->get_logger(), *this->get_clock(), 1, "Unknown converged param type."); - } - return is_ok_converged_param; -} - int NDTScanMatcher::count_oscillation( const std::vector & result_pose_msg_array) { @@ -744,7 +783,10 @@ std::array NDTScanMatcher::estimate_covariance( rot = find_rotation_matrix_aligning_covariance_to_principal_axes( ndt_result.hessian.inverse().block(0, 0, 2, 2)); } catch (const std::exception & e) { - RCLCPP_WARN(get_logger(), "Error in Eigen solver: %s", e.what()); + std::stringstream message; + message << "Error in Eigen solver: " << e.what(); + RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); + return param_.covariance.output_pose_covariance; } @@ -822,24 +864,53 @@ void NDTScanMatcher::add_regularization_pose(const rclcpp::Time & sensor_ros_tim interpolation_result_opt.value(); const Eigen::Matrix4f pose = pose_to_matrix4f(interpolation_result.interpolated_pose.pose.pose); ndt_ptr_->setRegularizationPose(pose); - RCLCPP_DEBUG_STREAM(get_logger(), "Regularization pose is set to NDT"); } void NDTScanMatcher::service_trigger_node( const std_srvs::srv::SetBool::Request::SharedPtr req, std_srvs::srv::SetBool::Response::SharedPtr res) { + diagnostics_trigger_node_->clear(); + diagnostics_trigger_node_->addKeyValue("service_call_time_stamp", this->now().seconds()); + is_activated_ = req->data; if (is_activated_) { initial_pose_buffer_->clear(); } res->success = true; + + diagnostics_trigger_node_->addKeyValue("is_activated", static_cast(is_activated_)); + diagnostics_trigger_node_->addKeyValue("is_succeed_service", res->success); + diagnostics_trigger_node_->publish(); } void NDTScanMatcher::service_ndt_align( const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res) { + diagnostics_ndt_align_->clear(); + + service_ndt_align_main(req, res); + + // check is_succeed_service + bool is_succeed_service = res->success; + diagnostics_ndt_align_->addKeyValue("is_succeed_service", is_succeed_service); + if (!is_succeed_service) { + std::stringstream message; + message << "ndt_align_service is failed."; + diagnostics_ndt_align_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + } + + diagnostics_ndt_align_->publish(); +} + +void NDTScanMatcher::service_ndt_align_main( + const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, + tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res) +{ + diagnostics_ndt_align_->addKeyValue("service_call_time_stamp", this->now().seconds()); + // get TF from pose_frame to map_frame const std::string & target_frame = param_.frame.map_frame; const std::string & source_frame = req->pose_with_covariance.header.frame_id; @@ -851,32 +922,50 @@ void NDTScanMatcher::service_ndt_align( // Note: Up to AWSIMv1.1.0, there is a known bug where the GNSS frame_id is incorrectly set to // "gnss_link" instead of "map". The ndt_align is designed to return identity when this issue // occurs. However, in the future, converting to a non-existent frame_id should be prohibited. - RCLCPP_WARN(this->get_logger(), "%s", ex.what()); - RCLCPP_WARN( - this->get_logger(), "Please publish TF %s to %s", target_frame.c_str(), source_frame.c_str()); - transform_s2t.header.stamp = get_clock()->now(); - transform_s2t.header.frame_id = target_frame; - transform_s2t.child_frame_id = source_frame; - transform_s2t.transform = tf2::toMsg(tf2::Transform::getIdentity()); + + diagnostics_ndt_align_->addKeyValue("is_succeed_transform_initial_pose", false); + + std::stringstream message; + message << "Please publish TF " << target_frame.c_str() << " to " << source_frame.c_str(); + diagnostics_ndt_align_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); + res->success = false; + return; } + diagnostics_ndt_align_->addKeyValue("is_succeed_transform_initial_pose", true); // transform pose_frame to map_frame const auto initial_pose_msg_in_map_frame = transform(req->pose_with_covariance, transform_s2t); - map_update_module_->update_map(initial_pose_msg_in_map_frame.pose.pose.position); + map_update_module_->update_map( + initial_pose_msg_in_map_frame.pose.pose.position, diagnostics_ndt_align_); // mutex Map std::lock_guard lock(ndt_ptr_mtx_); - if (ndt_ptr_->getInputTarget() == nullptr) { + // check is_set_map_points + bool is_set_map_points = (ndt_ptr_->getInputTarget() != nullptr); + diagnostics_ndt_align_->addKeyValue("is_set_map_points", is_set_map_points); + if (!is_set_map_points) { + std::stringstream message; + message << "No InputTarget. Please check the map file and the map_loader service"; + diagnostics_ndt_align_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); res->success = false; - RCLCPP_WARN( - get_logger(), "No InputTarget. Please check the map file and the map_loader service"); return; } - if (ndt_ptr_->getInputSource() == nullptr) { + // check is_set_sensor_points + bool is_set_sensor_points = (ndt_ptr_->getInputSource() != nullptr); + diagnostics_ndt_align_->addKeyValue("is_set_sensor_points", is_set_sensor_points); + if (!is_set_sensor_points) { + std::stringstream message; + message << "No InputSource. Please check the input lidar topic"; + diagnostics_ndt_align_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); res->success = false; - RCLCPP_WARN(get_logger(), "No InputSource. Please check the input lidar topic"); return; } @@ -1007,7 +1096,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose( result_pose_with_cov_msg.pose.pose = best_particle_ptr->result_pose; output_pose_with_cov_to_log(get_logger(), "align_pose_output", result_pose_with_cov_msg); - RCLCPP_DEBUG_STREAM(get_logger(), "best_score," << best_particle_ptr->score); + diagnostics_ndt_align_->addKeyValue("best_particle_score", best_particle_ptr->score); return result_pose_with_cov_msg; }