From 401a19423c8c8349fdef7e2d1962dc449ebecc32 Mon Sep 17 00:00:00 2001 From: NuoDaJia Date: Mon, 8 Dec 2025 10:01:16 +0800 Subject: [PATCH] first version of slam --- .../CMakeLists.txt | 97 + src/localization_module_lio_locus/README.md | 260 +++ .../apps/nodelets/CMakeLists.txt | 98 + .../nodelets/cloud_preprocessing_node.cpp | 125 ++ .../apps/nodelets/imu_preprocessing_node.cpp | 219 +++ .../apps/nodelets/lio_locus_node.cpp | 514 +++++ .../config/parameters_lio_locus.yaml | 150 ++ .../config/parameters_lio_locus_reloc.yaml | 150 ++ .../further_dev_flowchart_logic_locus.jpg | Bin 0 -> 591122 bytes .../figs/rosgraph_lio.png | Bin 0 -> 116615 bytes .../frontend_utils/CommonFunctions.h | 39 + .../frontend_utils/CommonStructs.h | 28 + .../geometry_utils/GeometryUtils.h | 160 ++ .../geometry_utils/GeometryUtilsMath.h | 201 ++ .../geometry_utils/GeometryUtilsROS.h | 211 +++ .../GeometryUtilsSerialization.h | 73 + .../geometry_utils/Matrix2x2.h | 117 ++ .../geometry_utils/Matrix3x3.h | 111 ++ .../geometry_utils/Matrix4x4.h | 209 +++ .../geometry_utils/MatrixNxMBase.h | 335 ++++ .../geometry_utils/MatrixNxNBase.h | 84 + .../geometry_utils/Quaternion.h | 134 ++ .../geometry_utils/Rotation2.h | 111 ++ .../geometry_utils/Rotation3.h | 223 +++ .../geometry_utils/RotationNBase.h | 61 + .../geometry_utils/Transform2.h | 117 ++ .../geometry_utils/Transform3.h | 125 ++ .../lio_locus_humble/geometry_utils/Vector2.h | 70 + .../lio_locus_humble/geometry_utils/Vector3.h | 87 + .../lio_locus_humble/geometry_utils/Vector4.h | 63 + .../geometry_utils/VectorNBase.h | 280 +++ .../geometry_utils/YAMLLoader.h | 106 ++ .../lio_locus_humble/ikd_tree/ikd_Tree.h | 240 +++ .../lio_locus/cloud_pre_processor.h | 127 ++ .../lio_locus/complementary_filter.h | 184 ++ .../lio_locus_humble/lio_locus/lio_locus.h | 231 +++ .../lio_locus/parameter_loading.h | 430 +++++ .../multithreaded_gicp/gicp.h | 443 +++++ .../multithreaded_gicp/gicp.hpp | 635 +++++++ .../multithreaded_ndt/ndt_omp.h | 537 ++++++ .../multithreaded_ndt/ndt_omp_impl.hpp | 1121 +++++++++++ .../voxel_grid_covariance_omp.h | 526 ++++++ .../voxel_grid_covariance_omp_impl.hpp | 487 +++++ .../PointCloudLocalization.h | 181 ++ .../point_cloud_localization/utils.h | 40 + .../point_cloud_mapper/IPointCloudMapper.h | 57 + .../PointCloudIkdTreeMapper.h | 64 + .../point_cloud_mapper/settings.h | 70 + .../point_cloud_odometry/PointCloudOdometry.h | 141 ++ .../lio_locus_humble/registration_settings.h | 20 + .../cloud_conversion.launch.cpython-38.pyc | Bin 0 -> 978 bytes .../cloud_preprocessing.launch.cpython-38.pyc | Bin 0 -> 980 bytes ..._preprocessing_livox.launch.cpython-38.pyc | Bin 0 -> 972 bytes .../lio_locus.launch.cpython-38.pyc | Bin 0 -> 957 bytes .../nodelets/cloud_preprocessing.launch.py | 34 + .../imu_preprocessing_livox.launch.py | 36 + .../launch/nodelets/lio_locus.launch.py | 36 + .../nodelets/vis_ego_viewpoint.launch.py | 22 + .../nodelets/vis_world_viewpoint.launch.py | 21 + src/localization_module_lio_locus/package.xml | 26 + .../rviz/ego_view_titan.rviz | 323 ++++ .../rviz/world_view_titan.rviz | 412 ++++ .../src/CMakeLists.txt | 5 + .../src/lio_locus/.lio_locus.cpp.swp | Bin 0 -> 16384 bytes .../src/lio_locus/CMakeLists.txt | 58 + .../src/lio_locus/cloud_pre_processor.cpp | 234 +++ .../src/lio_locus/complementary_filter.cpp | 543 ++++++ .../src/lio_locus/lio_locus.cpp | 590 ++++++ .../point_cloud_localization/CMakeLists.txt | 21 + .../PointCloudLocalization.cc | 420 +++++ .../src/point_cloud_localization/utils.cc | 163 ++ .../src/point_cloud_mapper/CMakeLists.txt | 27 + .../PointCloudIkdTreeMapper.cc | 148 ++ .../point_cloud_mapper/ikd_tree/ikd_Tree.cpp | 1663 +++++++++++++++++ .../src/point_cloud_odometry/CMakeLists.txt | 26 + .../PointCloudOdometry.cc | 307 +++ 76 files changed, 15207 insertions(+) create mode 100755 src/localization_module_lio_locus/CMakeLists.txt create mode 100755 src/localization_module_lio_locus/README.md create mode 100755 src/localization_module_lio_locus/apps/nodelets/CMakeLists.txt create mode 100755 src/localization_module_lio_locus/apps/nodelets/cloud_preprocessing_node.cpp create mode 100755 src/localization_module_lio_locus/apps/nodelets/imu_preprocessing_node.cpp create mode 100755 src/localization_module_lio_locus/apps/nodelets/lio_locus_node.cpp create mode 100755 src/localization_module_lio_locus/config/parameters_lio_locus.yaml create mode 100755 src/localization_module_lio_locus/config/parameters_lio_locus_reloc.yaml create mode 100755 src/localization_module_lio_locus/figs/further_dev_flowchart_logic_locus.jpg create mode 100755 src/localization_module_lio_locus/figs/rosgraph_lio.png create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/frontend_utils/CommonFunctions.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/frontend_utils/CommonStructs.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtils.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsMath.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsROS.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsSerialization.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix2x2.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix3x3.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix4x4.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/MatrixNxMBase.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/MatrixNxNBase.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Quaternion.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Rotation2.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Rotation3.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/RotationNBase.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Transform2.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Transform3.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector2.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector3.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector4.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/VectorNBase.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/YAMLLoader.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/ikd_tree/ikd_Tree.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/cloud_pre_processor.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/complementary_filter.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/lio_locus.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/parameter_loading.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_gicp/gicp.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_gicp/gicp.hpp create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/ndt_omp.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/ndt_omp_impl.hpp create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/voxel_grid_covariance_omp.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/voxel_grid_covariance_omp_impl.hpp create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_localization/PointCloudLocalization.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_localization/utils.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/IPointCloudMapper.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/PointCloudIkdTreeMapper.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/settings.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_odometry/PointCloudOdometry.h create mode 100755 src/localization_module_lio_locus/include/lio_locus_humble/registration_settings.h create mode 100755 src/localization_module_lio_locus/launch/__pycache__/cloud_conversion.launch.cpython-38.pyc create mode 100755 src/localization_module_lio_locus/launch/nodelets/__pycache__/cloud_preprocessing.launch.cpython-38.pyc create mode 100755 src/localization_module_lio_locus/launch/nodelets/__pycache__/imu_preprocessing_livox.launch.cpython-38.pyc create mode 100755 src/localization_module_lio_locus/launch/nodelets/__pycache__/lio_locus.launch.cpython-38.pyc create mode 100755 src/localization_module_lio_locus/launch/nodelets/cloud_preprocessing.launch.py create mode 100755 src/localization_module_lio_locus/launch/nodelets/imu_preprocessing_livox.launch.py create mode 100755 src/localization_module_lio_locus/launch/nodelets/lio_locus.launch.py create mode 100755 src/localization_module_lio_locus/launch/nodelets/vis_ego_viewpoint.launch.py create mode 100755 src/localization_module_lio_locus/launch/nodelets/vis_world_viewpoint.launch.py create mode 100755 src/localization_module_lio_locus/package.xml create mode 100755 src/localization_module_lio_locus/rviz/ego_view_titan.rviz create mode 100755 src/localization_module_lio_locus/rviz/world_view_titan.rviz create mode 100755 src/localization_module_lio_locus/src/CMakeLists.txt create mode 100755 src/localization_module_lio_locus/src/lio_locus/.lio_locus.cpp.swp create mode 100755 src/localization_module_lio_locus/src/lio_locus/CMakeLists.txt create mode 100755 src/localization_module_lio_locus/src/lio_locus/cloud_pre_processor.cpp create mode 100755 src/localization_module_lio_locus/src/lio_locus/complementary_filter.cpp create mode 100755 src/localization_module_lio_locus/src/lio_locus/lio_locus.cpp create mode 100755 src/localization_module_lio_locus/src/point_cloud_localization/CMakeLists.txt create mode 100755 src/localization_module_lio_locus/src/point_cloud_localization/PointCloudLocalization.cc create mode 100755 src/localization_module_lio_locus/src/point_cloud_localization/utils.cc create mode 100755 src/localization_module_lio_locus/src/point_cloud_mapper/CMakeLists.txt create mode 100755 src/localization_module_lio_locus/src/point_cloud_mapper/PointCloudIkdTreeMapper.cc create mode 100755 src/localization_module_lio_locus/src/point_cloud_mapper/ikd_tree/ikd_Tree.cpp create mode 100755 src/localization_module_lio_locus/src/point_cloud_odometry/CMakeLists.txt create mode 100755 src/localization_module_lio_locus/src/point_cloud_odometry/PointCloudOdometry.cc diff --git a/src/localization_module_lio_locus/CMakeLists.txt b/src/localization_module_lio_locus/CMakeLists.txt new file mode 100755 index 0000000..a605860 --- /dev/null +++ b/src/localization_module_lio_locus/CMakeLists.txt @@ -0,0 +1,97 @@ +cmake_minimum_required(VERSION 3.8) +project(lio_locus_humble) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +#add_compile_options(-std=c++17 -O3 -w) +add_compile_options(-std=c++17 -O3 -w -Wno-dev) +#add_compile_options(-std=c++11) + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(pcl_conversions REQUIRED) +find_package(tf2 REQUIRED) +find_package(tf2_ros REQUIRED) +find_package(std_srvs REQUIRED) + +find_package(Boost) +find_package(yaml-cpp 0.6 REQUIRED) +find_package(OpenMP) +find_package(Eigen3) + + +set(CMAKE_PREFIX_PATH "/home/demo/deps_install" ${CMAKE_PREFIX_PATH}) +set(CMAKE_INCLUDE_PATH "/home/demo/deps_install/include" ${CMAKE_INCLUDE_PATH}) +set(CMAKE_LIBRARY_PATH "/home/demo/deps_install/lib" ${CMAKE_LIBRARY_PATH}) + +set(PCL_DIR /home/demo/deps_install/share/pcl-1.10) + +set(PCL_ROOT /home/demo/deps_install) + +find_package(PCL REQUIRED) + +message("##################" ${PCL_INCLUDE_DIRS}) +message("##################" ${PCL_LIBRARIES}) +message("---------------------------"${PCL_INCLUDE_DIRS}) + +if (OPENMP_FOUND) + set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") + set (CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}") +endif() + +include_directories( + include/${PROJECT_NAME} + ${pcl_conversions_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} + ${PCL_INCLUDE_DIRS} + ${YAML_CPP_INCLUDE_DIR} + /user/include + /home/demo/deps_install/include/pcl-1.10 + ) + +link_directories( + /home/demo/deps_install/lib +) + + + +add_subdirectory(src) +#add_subdirectory(apps/nodelets) + +install( + DIRECTORY launch + DESTINATION share/${PROJECT_NAME} +) + +install( + DIRECTORY config + DESTINATION share/${PROJECT_NAME} +) + +install( + DIRECTORY rviz + DESTINATION share/${PROJECT_NAME} +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() + + diff --git a/src/localization_module_lio_locus/README.md b/src/localization_module_lio_locus/README.md new file mode 100755 index 0000000..92287fa --- /dev/null +++ b/src/localization_module_lio_locus/README.md @@ -0,0 +1,260 @@ +# LIO-Locus (Lidar Inertial Odometry) + +[TOC] + +## 1. Abstract + +​ This package is a CONCISE implementation for Loosely-Coupled LIO(LIDAR Inertial Odometry) based on open-source project LOCUS. + +* LIDAR Centric Sensor Sources: LIDAR sensor is centric in this approach, and IMU orientation value can be used as a prior for scan matching. However, IMU is not a necessity. Pure scan-only localization mode is also supported; +* Working Mode: this package can work in SLAM mode starting from scratch, and it can also work in PURE LOCALIZATION mode with prior map loaded from user specified path. + +Note: The PCL Library used in this code is PCL-1.10. + +## 2. ROS Wrapper + +​ ROS wrapper interfaces with ROS environment, subscribing raw sensor data and pass them to algorithm, then the estimation results from algorithm are returned to ROS environment: + +- Raw cloud data is pre-processed in way of voxel filtering and normal vector computation, and later fed to pose estimation algorithm for cloud registration; +- Raw IMU data is pre-processed with complementary filter for orientation estimation, and then can be optionally used as pose prior input for cloud registration; +- During cloud registration, robot pose could be estimated in SLAM mode with online-built cloud map and in PURE-LOCALIZATION model with previously uploaded cloud map. + +## 3. API (Application Programming Interfaces) + +### 3.0 Data Flow Graph + +​ The codes in app folder take the following forms: + +* Two independent pre-processing ROS nodes for cloud and IMU works together with state estimator ROS node, as illustrated in figure below: + +![](./figs/rosgraph_lio.png) + +### 3.1 Cloud Pre-Processor + +#### Parameter Loading + +* header file inclusion + +``` +#include "lio_locus/parameter_loading.h" +``` + +* parameter structure loading + +``` +bool loadParametersFromFileForCloudPreprocessing(std::string path_to_file, ParameterCloudPreprocessing & params_cloud_preproc); +``` + +#### Functionalities + +* header file inclusion + +``` +#include "lio_locus/cloud_pre_processor.h" +``` + +* set basic parameters for cloud pre-processor; + +``` +void CloudPreProcessor::setCloudPreProcessingParameters + (double leaf_voxel_filtering, double filter_limit, size_cores, int size_k_search, double radius_search) +``` + +* to transform cloud to target frame and compute associated normal vectors: + +``` +bool CloudPreProcessor::transformCloudWithNormalCalculation + (pcl::PointCloud::Ptr cloud_input, tf2::Transform T, + pcl::PointCloud::Ptr &cloud_normals); +``` + +### 3.2 IMU Pre-Processor + +#### Parameter Loading + +* header file inclusion + +``` +#include "lio_locus/parameter_loading.h" +``` + +* parameter structure loading + +``` +bool loadParametersFromFileForIMUPreprocessing(std::string path_to_file, ParameterImuPreprocessing ¶ms_imu_preproc) +``` + +#### Functionalities + +* parameter setting + +``` +void ComplementaryFilter::setDoBiasEstimation(bool do_bias_estimation) +``` + +``` +void ComplementaryFilter::setDoAdaptiveGain(bool do_adaptive_gain) +``` + +* observation update + +``` +void ComplementaryFilter::update(double ax, double ay, double az, double wx, double wy, double wz, double dt) +``` + +* orientation retrieval + +``` +void ComplementaryFilter::getOrientation(double& q0, double& q1, double& q2, double& q3) const +``` + +### 3.3 LIO-Locus + +#### Parameter Loading + +* header file inclusion + +``` +#include "lio_locus/lio_locus.h" +``` + +* parameter structure loading + +``` +bool loadParametersFromFileForLioLocus(std::string path_to_file, ParameterLioLocus& params_lio_locus) +``` + +#### Initialization + +``` +bool LioLocus::initialize(string path_to_param); +``` + +#### Parameter Setting + +* set flag to use IMU data or not; + +``` +void LioLocus::setUseIMU(bool flag) +``` + +* set flag to use consecutive scan matching or not; + +``` +void LioLocus::setUseScan2ScanMatching(bool flag) +``` + +* set threshold values as input arguments for translation and rotation to insert new localized cloud to cloud map: + +``` +void LioLocus::setThresholds(double trans, double rot) +``` + +* set relative rotation from IMU frame id to lidar cloud frame id: + +``` +void LioLocus::setIMU2CloudExtrinsic(Eigen::Quaterniond quat) +``` + +* set flag to use flat ground assumption or not; + +``` +void LioLocus::setFlatGroundAssumption(bool flag) +``` + +#### Functionalities: + +##### SLAM Mode with Online Built Map + +* start from scratch without any cloud map in memory, and cloud map is updated online: + +``` +void LioLocus::trackCurrentCloudWithOnlineBuiltMap(PointCloudType::Ptr msg_cloud); +``` + +##### Pure Localization Mode with Loaded Cloud Map + +* to fresh memory cloud with data storage: + +``` +bool LioLocus::uploadPriorCloudMap(string fn_cloud_map, double leaf_size); +``` + +* for re-localization when prior cloud map is loaded in advance: + +``` +void LioLocus::setPosePrior(geometry_utils::Transform3 pose_prior); +``` + +* cloud map in memory is not updated; + +``` +bool LioLocus::trackCurrentCloudWithPriorCloudMap(PointCloudType::Ptr msg_cloud); +``` + +* clear map stored in memory: + +``` +void LioLocus::clearCloudMapInMemory(); +``` + +#### Data Retrieval + +##### Time Stamped Pose + +* get time-stamped robot pose: + +``` +inline TransformStamped getTimestampedLatestPose(){ + return m_pose_latest; +} +``` + +##### Localized Cloud + +* get latest localized cloud registered against cloud map in memory: + +``` +PointCloudType::Ptr getLatestLocalizedCloud() +``` + +##### Cloud Map + +* get cloud map stored in memory in form of Point Cloud: + +``` +bool getCloudMapInMemory(PointCloudType::Ptr cloud, double voxel_size = 0.5) +``` + +## 4. Algorithm Structure + +The logics for data flow within structure of LIO-Locus is illustrated in figure below. The blue blocks are cloud map construction steps, and the magenta blocks are cloud registration steps, including scan-to-scan matching and scan-to-map matching. + +![](./figs/further_dev_flowchart_logic_locus.jpg) + +## 5. Summary + +​ This package constructs algorithm stuff as stand-alone cpp class, feeding LIDAR cloud data and optionally IMU data into algorithm for data processing. + +​ The 6 DOF (Degree of Freedom) pose of the robot together with online localized cloud, the cloud map in form of PCL data format, can be retrieved for further application such as navigation and so on. + +## 6. Acknowledgement + +​ The developer of the code shows great thanks and respect to the original open-source code LOCUS. + + + + + + + + + + + + + + + + + diff --git a/src/localization_module_lio_locus/apps/nodelets/CMakeLists.txt b/src/localization_module_lio_locus/apps/nodelets/CMakeLists.txt new file mode 100755 index 0000000..cbed26c --- /dev/null +++ b/src/localization_module_lio_locus/apps/nodelets/CMakeLists.txt @@ -0,0 +1,98 @@ + +add_executable(lio_locus_node lio_locus_node.cpp) + +target_link_libraries(lio_locus_node + ${PROJECT_NAME} + point_cloud_odometry + point_cloud_localization + point_cloud_mapper + boost_filesystem +) + +target_include_directories(lio_locus_node PUBLIC + $ + $) + +target_compile_features( lio_locus_node PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 + +ament_target_dependencies( + lio_locus_node + "rclcpp" + # "std_msgs" + "sensor_msgs" + "nav_msgs" + "pcl_conversions" + "std_srvs" + "tf2" + #"tf2_ros" +) + +# install exe to folder within lib; +install(TARGETS lio_locus_node + DESTINATION lib/${PROJECT_NAME} + ) + + + +# install exe to folder within lib; +install(TARGETS lio_locus_node + DESTINATION lib/${PROJECT_NAME} + ) +#-------------------------------------------------------- +add_executable(imu_preprocessing_node imu_preprocessing_node.cpp) +ament_target_dependencies(imu_preprocessing_node rclcpp sensor_msgs) + +target_link_libraries(imu_preprocessing_node + complementary_filter + ${YAML_CPP_LIBRARIES} + boost_filesystem +) + +target_include_directories(imu_preprocessing_node PUBLIC + $ + $) + +target_compile_features(imu_preprocessing_node PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 + +ament_target_dependencies( + imu_preprocessing_node + "rclcpp" + # "std_msgs" + "sensor_msgs" + "nav_msgs" + #"pcl_conversions" + #"tf2" + "tf2_ros" +) + +install(TARGETS imu_preprocessing_node + DESTINATION lib/${PROJECT_NAME}) +#------------------------------------- +add_executable(cloud_preprocessing_node cloud_preprocessing_node.cpp) + +target_link_libraries(cloud_preprocessing_node + cloud_pre_processor + boost_filesystem +) + +#target_include_directories(cloud_preprocessing_node PUBLIC +# $ +# $) + +target_compile_features(cloud_preprocessing_node PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 + +ament_target_dependencies( + cloud_preprocessing_node + "rclcpp" + # "std_msgs" + "sensor_msgs" + #"nav_msgs" + #"pcl_conversions" + "tf2" + #"tf2_ros" +) + +install(TARGETS cloud_preprocessing_node + DESTINATION lib/${PROJECT_NAME} + ) +# diff --git a/src/localization_module_lio_locus/apps/nodelets/cloud_preprocessing_node.cpp b/src/localization_module_lio_locus/apps/nodelets/cloud_preprocessing_node.cpp new file mode 100755 index 0000000..d7b209b --- /dev/null +++ b/src/localization_module_lio_locus/apps/nodelets/cloud_preprocessing_node.cpp @@ -0,0 +1,125 @@ + +/* + * Author: Solomon + * Date: Oct. 20, 2025, + * + */ + +/* + * functionality: pre-processing of cloud for more sparse and normal-vectorized cloud; + * inputs: lidar cloud, transformation from lidar frame id to target frame id, and parameters; + * outputs: pre-processing cloud after voxel grid filtering and normal vector calculation; + * + * note: transformation can also be retrieved from IMU message; + */ + +//================================================================================ +// algorithm stuff; +#include "lio_locus/cloud_pre_processor.h" +ParameterCloudPreprocessing params_cloud_preproc; +tf2::Transform T_base2laser; +CloudPreProcessor::Ptr ptr_cloud_pre_processor; +//================================================================================ +// ROS stuff; +#include +#include +#include +#include +#include +#include +#include + +using std::string; + +void callbackLidarRaw(const sensor_msgs::msg::PointCloud2 &msg); +rclcpp::Publisher::SharedPtr pub_cloud_preprocessed; +rclcpp::Publisher::SharedPtr pub_dt_cloud_preproc; + +int main(int argc, char **argv) +{ + // node for subscription of cloud; + rclcpp::init(argc, argv); + rclcpp::Node::SharedPtr node = std::make_shared("cloud_preprocessing_node"); + + // loading parameters for LIO-Locus; + string path_to_param_file; + node->declare_parameter("file_params", "/home/solomon/ws_humble_pcl_10/src/lio_locus_humble/config/parameters_lio_locus.yaml"); + path_to_param_file = node->get_parameter("file_params").as_string(); + + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_cloud_preproc.log_tag), "... file params -> #[" + << path_to_param_file << "]"); + //================================================================================ + // algorithm instantiation; + ParameterCloudPreprocessing params_cloud_preproc; + loadParametersFromFileForCloudPreprocessing(path_to_param_file, params_cloud_preproc); + T_base2laser.setOrigin(tf2::Vector3(params_cloud_preproc.ext_tx, params_cloud_preproc.ext_ty, params_cloud_preproc.ext_tz)); + tf2::Quaternion q; + q.setRPY(params_cloud_preproc.ext_roll, params_cloud_preproc.ext_pitch, params_cloud_preproc.ext_yaw); + T_base2laser.setRotation(q); + ptr_cloud_pre_processor = CloudPreProcessor::Ptr(new CloudPreProcessor()); + ptr_cloud_pre_processor->setCloudPreProcessingParameters(params_cloud_preproc.leaf_voxel_filtering, params_cloud_preproc.filter_limit, + params_cloud_preproc.size_cores, + params_cloud_preproc.size_k_search_knn, params_cloud_preproc.radius_search_knn); + ptr_cloud_pre_processor->setLogPath(params_cloud_preproc.path_log); + //================================================================================ + + rclcpp::Subscription::SharedPtr sub_cloud_raw = + node->create_subscription(params_cloud_preproc.topic_cloud_raw, 9, callbackLidarRaw); + pub_cloud_preprocessed = node->create_publisher(params_cloud_preproc.topic_cloud, 9); + pub_dt_cloud_preproc = node->create_publisher("/dt_cloud_preprocessing", 9); + + rclcpp::spin(node); + + return 0; +} + +void callbackLidarRaw(const sensor_msgs::msg::PointCloud2 &msg) +{ + + rclcpp::Time current_time; + current_time = rclcpp::Clock().now(); + double seconds_start = current_time.seconds(); + + //================================================================================ + // transform cloud from ROS format to PCL format; + pcl::PointCloud::Ptr cloud_raw( + new pcl::PointCloud()); + + if(params_cloud_preproc.topic_cloud_raw == "/rsm1_1") + { + cloud_raw = CloudPreProcessor::adaptCloudForm(msg); + }else if (params_cloud_preproc.topic_cloud_raw == "/livox/lidar"){ + cloud_raw = CloudPreProcessor::adaptCloudFormFromLivoxCloud(msg); + } + + pcl::PointCloud::Ptr cloud_normals( + new pcl::PointCloud()); + ptr_cloud_pre_processor->transformCloudWithNormalCalculation(cloud_raw, + T_base2laser, cloud_normals); + //================================================================================ + + current_time = rclcpp::Clock().now(); + double seconds_end = current_time.seconds(); + double dt = seconds_end - seconds_start; + dt *= 1e3; + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_cloud_preproc.log_tag), + "... time passed for cloud pre-processing: [" << dt << "] ms"); + + // // publish time elapsed; + // geometry_msgs::msg::Vector3Stamped msg_dt; + // msg_dt.header.stamp = msg.header.stamp; + // msg_dt.vector.x = dt; + // pub_dt_cloud_preproc->publish(msg_dt); + + sensor_msgs::msg::PointCloud2 msg_cloud_ros2; + pcl::toROSMsg(*cloud_normals, msg_cloud_ros2); + msg_cloud_ros2.header.stamp = msg.header.stamp; + msg_cloud_ros2.header.frame_id = params_cloud_preproc.frame_id_base; + pub_cloud_preprocessed->publish(msg_cloud_ros2); + + // current_time = rclcpp::Clock().now(); + // double seconds_end2 = current_time.seconds(); + // dt = seconds_end2 - seconds_end; + // RCLCPP_INFO_STREAM(rclcpp::get_logger(params_cloud_preproc.log_tag), + // "... time passed for cloud format conversion: [" << dt * 1e3 << "] ms"); +} diff --git a/src/localization_module_lio_locus/apps/nodelets/imu_preprocessing_node.cpp b/src/localization_module_lio_locus/apps/nodelets/imu_preprocessing_node.cpp new file mode 100755 index 0000000..889eac1 --- /dev/null +++ b/src/localization_module_lio_locus/apps/nodelets/imu_preprocessing_node.cpp @@ -0,0 +1,219 @@ + +/* + * Author: Solomon + * Date: Oct. 20, 2025, + * + */ + +/* + * functionality: pre-processing IMU data for orientation; + * input: IMU content with linear accelerator values and gyroscope values; + * output: compensated IMU data with orientation from filter; + */ + +//================================================================================ +// algorithm stuff; +#include "lio_locus/complementary_filter.h" +ParameterImuPreprocessing params_imu_preproc; +imu_tools::ComplementaryFilter filter_; +//================================================================================ +// ROS stuff; + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include + +using std::string; + +typedef sensor_msgs::msg::Imu ImuMsg; +void callbackImuRaw(const sensor_msgs::msg::Imu &msg); +void publish(ImuMsg imu_msg_raw); +rclcpp::Publisher::SharedPtr rpy_publisher_; +rclcpp::Publisher::SharedPtr state_publisher_; +rclcpp::Publisher::SharedPtr imu_publisher_; +rclcpp::Publisher::SharedPtr dt_publisher_; +double orientation_variance_; +bool reverse_tf_; +tf2::Quaternion hamiltonToTFQuaternion(double q0, double q1, double q2, + double q3); +boost::shared_ptr tf_broadcaster_; + +int main(int argc, char **argv) +{ + // ROS parameter stuff; + rclcpp::init(argc, argv); + rclcpp::Node::SharedPtr node = std::make_shared("imu_preprocessing_node"); + tf_broadcaster_ = boost::shared_ptr(new tf2_ros::TransformBroadcaster(node)); + + string path_to_param_file; + node->declare_parameter("file_params", "/home/solomon/ws_humble_pcl_10/src/lio_locus_humble/config/parameters_lio_locus.yaml"); + path_to_param_file = node->get_parameter("file_params").as_string(); + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_imu_preproc.log_tag), "... parameter path -> [" << path_to_param_file << "]"); + + //================================================================================ + // algorithm stuff for initialization; + loadParametersFromFileForIMUPreprocessing(path_to_param_file, params_imu_preproc); + filter_.setDoBiasEstimation(params_imu_preproc.do_bias_estimation); + filter_.setDoAdaptiveGain(params_imu_preproc.do_adaptive_gain); + if (params_imu_preproc.do_bias_estimation) + { + if (!filter_.setBiasAlpha(params_imu_preproc.bias_alpha)) + RCLCPP_WARN(node->get_logger(), + "Invalid bias_alpha passed to ComplementaryFilter."); + } + orientation_variance_ = params_imu_preproc.orientation_stddev * params_imu_preproc.orientation_stddev; + filter_.setLogPath(params_imu_preproc.path_log); + //================================================================================ + // ROS stuff; + rclcpp::Subscription::SharedPtr sub_imu = + node->create_subscription(params_imu_preproc.topic_imu_raw, 9, callbackImuRaw); + rpy_publisher_ = node->create_publisher("imu/rpy/filtered", 9); + state_publisher_ = node->create_publisher("imu/steady_state", 9); + imu_publisher_ = node->create_publisher("/imu_filtered", 9); + dt_publisher_ = node->create_publisher("/dt_imu_preprocessing",9); + + rclcpp::spin(node); + + return 0; +} + +// feeding raw data for orientation estimation; +void callbackImuRaw(const sensor_msgs::msg::Imu &imu_msg_raw) +{ + + + // compute time difference; + static auto initialized_filter_ = false; + static double t_secs_prev_; + const rclcpp::Time &time = imu_msg_raw.header.stamp; + // Initialize. + if (!initialized_filter_) + { + t_secs_prev_ = time.seconds(); + initialized_filter_ = true; + return; + } + + double dt = (time.seconds() - t_secs_prev_); + t_secs_prev_ = time.seconds(); + + rclcpp::Time current_time; + current_time = rclcpp::Clock().now(); + double seconds_start = current_time.seconds(); + //================================================================================ + const geometry_msgs::msg::Vector3 &a = imu_msg_raw.linear_acceleration; + const geometry_msgs::msg::Vector3 &w = imu_msg_raw.angular_velocity; + filter_.update(a.x, a.y, a.z, w.x, w.y, w.z, dt); + //================================================================================ + current_time = rclcpp::Clock().now(); + double seconds_end = current_time.seconds(); + dt = seconds_end - seconds_start; + + dt *= 1e3; + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_imu_preproc.log_tag), + "... time passed for imu pre-processing: [" << dt << "] ms"); + + geometry_msgs::msg::Vector3Stamped msg_dt; + msg_dt.header.stamp = imu_msg_raw.header.stamp; + msg_dt.vector.x = dt; + dt_publisher_->publish(msg_dt); + + publish(imu_msg_raw); +} + +tf2::Quaternion hamiltonToTFQuaternion(double q0, double q1, double q2, + double q3) +{ + // ROS uses the Hamilton quaternion convention (q0 is the scalar). However, + // the ROS quaternion is in the form [x, y, z, w], with w as the scalar. + return tf2::Quaternion(q1, q2, q3, q0); +} + +void publish(ImuMsg imu_msg_raw) +{ + // Get the orientation: + double q0, q1, q2, q3; + filter_.getOrientation(q0, q1, q2, q3); + + // formulate IMU msg with raw data and estimated orientation; + ImuMsg::SharedPtr imu_msg = std::make_shared(imu_msg_raw); + imu_msg->orientation.x = q1; + imu_msg->orientation.y = q2; + imu_msg->orientation.z = q3; + imu_msg->orientation.w = q0; + + imu_msg->orientation_covariance[0] = orientation_variance_; + imu_msg->orientation_covariance[1] = 0.0; + imu_msg->orientation_covariance[2] = 0.0; + imu_msg->orientation_covariance[3] = 0.0; + imu_msg->orientation_covariance[4] = orientation_variance_; + imu_msg->orientation_covariance[5] = 0.0; + imu_msg->orientation_covariance[6] = 0.0; + imu_msg->orientation_covariance[7] = 0.0; + imu_msg->orientation_covariance[8] = orientation_variance_; + + // Account for biases. + if (filter_.getDoBiasEstimation()) + { + imu_msg->angular_velocity.x -= filter_.getAngularVelocityBiasX(); + imu_msg->angular_velocity.y -= filter_.getAngularVelocityBiasY(); + imu_msg->angular_velocity.z -= filter_.getAngularVelocityBiasZ(); + } + + imu_publisher_->publish(*imu_msg); + + // Create and publish roll, pitch, yaw angles + geometry_msgs::msg::Vector3Stamped rpy; + rpy.header = imu_msg_raw.header; + tf2::Quaternion q = hamiltonToTFQuaternion(q0, q1, q2, q3); + tf2::Matrix3x3 M; + M.setRotation(q); + M.getRPY(rpy.vector.x, rpy.vector.y, rpy.vector.z); + rpy_publisher_->publish(rpy); + + // Publish whether we are in the steady state, when doing bias + // estimation + if (filter_.getDoBiasEstimation()) + { + std_msgs::msg::Bool state_msg; + state_msg.data = filter_.getSteadyState(); + state_publisher_->publish(state_msg); + } + + if (params_imu_preproc.flag_publish_tf) + { + // Create and publish the ROS tf. + geometry_msgs::msg::TransformStamped transform; + transform.header.stamp = imu_msg_raw.header.stamp; + transform.transform.rotation.x = q1; + transform.transform.rotation.y = q2; + transform.transform.rotation.z = q3; + transform.transform.rotation.w = q0; + + if (reverse_tf_) + { + transform.header.frame_id = imu_msg_raw.header.frame_id; + transform.child_frame_id = params_imu_preproc.frame_fixed; + tf_broadcaster_->sendTransform(transform); + } + else + { + transform.child_frame_id = imu_msg_raw.header.frame_id; + transform.header.frame_id = params_imu_preproc.frame_fixed; + tf_broadcaster_->sendTransform(transform); + } + } +} diff --git a/src/localization_module_lio_locus/apps/nodelets/lio_locus_node.cpp b/src/localization_module_lio_locus/apps/nodelets/lio_locus_node.cpp new file mode 100755 index 0000000..5bbfcc9 --- /dev/null +++ b/src/localization_module_lio_locus/apps/nodelets/lio_locus_node.cpp @@ -0,0 +1,514 @@ + +/* + * Author: Solomon + * Date: Oct. 20, 2025, + * + */ + +/* + * functionality: loosely-couple lidar inertial odometry; + * input: pre-processed cloud with normal vector information and pre-processed IMU with orientations; + * output: estimated robot pose, recorded trajectory, localized cloud and cloud map; + */ + +//============================================================================== +#include "lio_locus/lio_locus.h" +ParameterLioLocus params_lio_locus; +using lio_locus::LioLocus; +LioLocus::Ptr ptr_lio_locus; +//============================================================================== + +// ROS2 stuff; +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using std::string; + +bool flag_init_pose_set; +typedef sensor_msgs::msg::Imu ImuMsg; +void callbackLidar(const sensor_msgs::msg::PointCloud2 &msg); +void callbackInitialGuess(const geometry_msgs::msg::PoseWithCovarianceStamped &msg); +void callbackPublishIncrementals(); +void callbackPublishMap(); +void callbackProcessData(); +void callbackImu(const ImuMsg &msg); +rclcpp::Publisher::SharedPtr pub_localized_cloud; +rclcpp::Publisher::SharedPtr pub_cloud_map; +rclcpp::Publisher::SharedPtr pub_path; +rclcpp::Publisher::SharedPtr pub_pose_array; + +rclcpp::Publisher::SharedPtr pub_pose; +rclcpp::Publisher::SharedPtr dt_publisher_; +void publishRobotPose(); +void publishLocalizedCloud(); +void publishCloudMap(rclcpp::Time ts); +void processCloud4Localization(pcl::PointCloud::Ptr p_cloud); + + + +void recordRobotTrajectory(rclcpp::Time ts, + const geometry_utils::Transform3 ¤t_pose, double threshold_trans, double threshold_rot, + nav_msgs::msg::Path& path , geometry_msgs::msg::PoseArray& pose_array); + +// for cloud data storage; +typedef pcl::PointCloud PointCloudNormal; +#include +std::deque deq_clouds; + +#include + +#include + +bool flag_invoke_saving_map; + +void serviceInvoking(const std::shared_ptr request, + std::shared_ptr response) +{ + flag_invoke_saving_map = true; + + ptr_lio_locus->saveCloudMapInMemory(params_lio_locus.path_save_map, params_lio_locus.flag_voxel_filtering, params_lio_locus.leaf_size); + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "################## service invoked: !!! "); +} + +int main(int argc, char **argv) +{ + + flag_invoke_saving_map = false; + + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), "###########!!!!!!######################"); + + rclcpp::Node::SharedPtr node; + + // node for subscription of cloud and IMU; + rclcpp::init(argc, argv); + + node = std::make_shared("lio_locus_node"); + + // algorithm initialization stuff; + flag_init_pose_set = false; + + string path_to_param_file; + node->declare_parameter("file_params", "/home/solomon/ws_humble_pcl_10/src/lio_locus_humble/config/parameters_lio_locus.yaml"); + path_to_param_file = node->get_parameter("file_params").as_string(); + + rclcpp::Service::SharedPtr service = + node->create_service("invoke_saving_map", &serviceInvoking); + + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), "... file params -> #[" + << path_to_param_file << "]"); + //============================================================================== + loadParametersFromFileForLioLocus(path_to_param_file, params_lio_locus); + + // algorithm initialization; + ptr_lio_locus = LioLocus::Ptr(new LioLocus()); + ptr_lio_locus->initialize(path_to_param_file); + ptr_lio_locus->setUseIMU(params_lio_locus.flag_use_imu); + // set extrinsic for imu2lidar; + tf2::Quaternion q_imu2lidar_ext; + q_imu2lidar_ext.setRPY(params_lio_locus.ext_imu2lidar_droll, params_lio_locus.ext_imu2lidar_dpitch, params_lio_locus.ext_imu2lidar_dyaw); + Eigen::Quaterniond q_imu2lidar(q_imu2lidar_ext.w(), q_imu2lidar_ext.x(), q_imu2lidar_ext.y(), q_imu2lidar_ext.z()); + ptr_lio_locus->setIMU2CloudExtrinsic(q_imu2lidar); + ptr_lio_locus->printIMU2CloudExtrinsic(); + + if (params_lio_locus.flag_use_scan2scan_matching) + ptr_lio_locus->setUseScan2ScanMatching(params_lio_locus.flag_use_scan2scan_matching); + ptr_lio_locus->setThresholds(params_lio_locus.threshold_trans_map, params_lio_locus.threshold_rot_map); + + // when use prior map, + if (params_lio_locus.flag_use_prior_map) + { + ptr_lio_locus->uploadPriorCloudMap(params_lio_locus.fn_cloud_map, params_lio_locus.leaf_size_load_map); + + // set initial pose; + geometry_utils::Transform3 pose_prior = geometry_utils::Transform3::Identity(); + ptr_lio_locus->setPosePrior(pose_prior); + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), "... setting initial pose -> [" + << pose_prior.translation.X() << "," << pose_prior.translation.Y() << "," << pose_prior.translation.Z() << "],[" + << pose_prior.rotation.Roll() << "," << pose_prior.rotation.Pitch() << "," << pose_prior.rotation.Yaw() << "]"); + } + ptr_lio_locus->setPathLog(params_lio_locus.path_log); + + //=============================================================================== + rclcpp::Subscription::SharedPtr sub_cloud; + sub_cloud = node->create_subscription(params_lio_locus.topic_cloud, 9, callbackLidar); + + rclcpp::Subscription::SharedPtr sub_imu; + sub_imu = node->create_subscription(params_lio_locus.topic_imu, 9, callbackImu); + + // for initial guess of pose prior; + rclcpp::Subscription::SharedPtr sub_initial_guess = + node->create_subscription("/initialpose", 9, callbackInitialGuess); + + pub_pose = node->create_publisher("pose_lo", 9); + pub_localized_cloud = + node->create_publisher("/dbg_localized_cloud", 9); + + + + + + pub_path = node->create_publisher("/dbg_lio_path", 9); + pub_pose_array = node->create_publisher("/dbg_lio_pose_array", 9); + + pub_cloud_map = + node->create_publisher("/cloud_map", 9); + + dt_publisher_ = node->create_publisher("/dt_lio_locus", 9); + + // independent threads for data processing, incrementals publication, map publication; + // rclcpp::TimerBase::SharedPtr p_process_data = node->create_wall_timer(std::chrono::milliseconds(100), callbackProcessData); + rclcpp::TimerBase::SharedPtr p_publish_incrementals = node->create_wall_timer(std::chrono::milliseconds(200), callbackPublishIncrementals); + rclcpp::TimerBase::SharedPtr p_publish_map = node->create_wall_timer(std::chrono::milliseconds(5000), callbackPublishMap); + + // multi-threaded spinners; + rclcpp::executors::MultiThreadedExecutor::SharedPtr threaded = std::make_shared(); + threaded->add_node(node); + threaded->spin(); + + rclcpp::shutdown(); + return 0; +} + +// store input clouds to memory for later processing; +void callbackLidar(const sensor_msgs::msg::PointCloud2 &msg) +{ + PointCloudType::Ptr p_cloud(new PointCloudType()); + pcl::fromROSMsg(msg, *p_cloud); + + processCloud4Localization(p_cloud); + + // deq_clouds.push_back(p_cloud); +} + +void callbackProcessData() +{ + + boost::mutex mutex_; + boost::mutex::scoped_lock lock(mutex_); + + if (!deq_clouds.size()) + return; + + PointCloudNormal::Ptr p_cloud = deq_clouds.front(); + processCloud4Localization(p_cloud); + + deq_clouds.pop_front(); +} + +// do data processing, publish estimated pose and localized cloud; +void callbackPublishIncrementals() +{ + + // publish algorithm result for visualization; + publishRobotPose(); + publishLocalizedCloud(); +} + +void callbackPublishMap() +{ + publishCloudMap(rclcpp::Clock().now()); +} + +void callbackInitialGuess(const geometry_msgs::msg::PoseWithCovarianceStamped &msg) +{ + + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), "... initial guess for pose prior is given!"); + + if (!params_lio_locus.flag_use_prior_map) + return; + + auto p = msg.pose.pose.position; + auto q = msg.pose.pose.orientation; + + geometry_utils::Transform3 pose_prior(geometry_utils::Vec3d(p.x, p.y, p.z), + geometry_utils::Quaterniond(q.w, q.x, q.y, q.z)); + ptr_lio_locus->setPosePrior(pose_prior); + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), "... setting initial pose -> [" + << pose_prior.translation.X() << "," << pose_prior.translation.Y() << "," << pose_prior.translation.Z() << "],[" + << pose_prior.rotation.Roll() << "," << pose_prior.rotation.Pitch() << "," << pose_prior.rotation.Yaw() << "]"); + + flag_init_pose_set = true; +} + +// imu subscription callback; +void callbackImu(const ImuMsg &msg) +{ + lio_locus::IMUData imu_data(msg.header.stamp.sec, + msg.orientation.x, msg.orientation.y, msg.orientation.z, msg.orientation.w); + + ptr_lio_locus->feedIMUData(imu_data); +} + +void processCloud4Localization(PointCloudNormal::Ptr p_cloud) +{ + + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), "##################################################################"); + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), "... start processing cloud with normal vector obtained: #[" + << p_cloud->size() << "] points"); + + //============================================================================== + double seconds_start = rclcpp::Clock().now().seconds(); + // cloud feeding to algorithm; + if (params_lio_locus.flag_use_prior_map) + { + + if (flag_init_pose_set) + { + ptr_lio_locus->trackCurrentCloudWithPriorCloudMap(p_cloud); + } + } + else + + { + ptr_lio_locus->trackCurrentCloudWithOnlineBuiltMap(p_cloud); + } + + double seconds_end = rclcpp::Clock().now().seconds(); + double dt = seconds_end - seconds_start; + dt *= 1e3; + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), + "############## time passed for LIO processing: [" << dt << "] ms ##############"); + + //============================================================================== + // publish results; + rclcpp::Time time_now; + pcl_conversions::fromPCL(p_cloud->header.stamp, time_now); + + geometry_msgs::msg::Vector3Stamped msg_dt; + msg_dt.header.stamp = time_now; + msg_dt.vector.x = dt; + dt_publisher_->publish(msg_dt); +} + +// ROS function to publish cloud map at times; +void publishCloudMap(rclcpp::Time ts) +{ + + // do voxel grid filtering at times; + double seconds_start = rclcpp::Clock().now().seconds(); + + PointCloudType::Ptr ptr_cloud_map(new PointCloudType()); + if (!ptr_lio_locus->getCloudMapInMemory(ptr_cloud_map)) + return; + + + if(!ptr_cloud_map->size()) + return ; + + // check: normal vector information ; + + +// if(flag_invoke_saving_map) +// { +// pcl::io::savePCDFileASCII(params_lio_locus.path_save_map, *ptr_cloud_map); +// flag_invoke_saving_map = false; +// } + + // // for first time and for time when size doubles; + // static bool flag_recorded = false; + // static int size_cloud_map; + // int size_now = ptr_cloud_map->size(); + + // bool flag_publish = false; + // if (!flag_recorded) + // { + // flag_publish = true; + // size_cloud_map = size_now; + // } + // else + // { + // if (size_now > 1.6 * size_cloud_map) + // { + // size_cloud_map = size_now; + // flag_publish = true; + // } + // } + + // flag_recorded = true; + + // if (!flag_publish) + // return; + + // voxel grid filtering for cloud map; + PointCloudType::Ptr cloud_downsampled = LioLocus::downsampleCloud(ptr_cloud_map, params_lio_locus.leaf_size_vis_map); + + sensor_msgs::msg::PointCloud2 msg_cloud_map; + pcl::toROSMsg(*cloud_downsampled, msg_cloud_map); + msg_cloud_map.header.stamp = ts; + msg_cloud_map.header.frame_id = params_lio_locus.frame_id_world; + + // publish to ROS2 env. + pub_cloud_map->publish(msg_cloud_map); + + double seconds_end = rclcpp::Clock().now().seconds(); + double dt = seconds_end - seconds_start; + dt *= 1e3; + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), + "############## time passed for cloud map publication: [" << dt << "] ms ##############"); +} + +void publishRobotPose() +{ + auto pose = ptr_lio_locus->getTimestampedLatestPose().pose; + + nav_msgs::msg::Odometry msg_pose; + auto &p = msg_pose.pose.pose.position; + p.x = pose.translation.X(); + p.y = pose.translation.Y(); + p.z = pose.translation.Z(); + + auto &q = msg_pose.pose.pose.orientation; + tf2::Quaternion q_tf2; + q_tf2.setRPY(pose.rotation.Roll(), pose.rotation.Pitch(), pose.rotation.Yaw()); + q.x = q_tf2.x(); + q.y = q_tf2.y(); + q.z = q_tf2.z(); + q.w = q_tf2.w(); + + rclcpp::Time time_now; + pcl_conversions::fromPCL(ptr_lio_locus->getTimestampedLatestPose().timestamp, time_now); + + msg_pose.header.stamp = time_now; + msg_pose.header.frame_id = params_lio_locus.frame_id_world; + pub_pose->publish(msg_pose); + + bool flag_record_traj = false; + if (!params_lio_locus.flag_use_prior_map) + { + flag_record_traj = true; + } + + // publish path travelled so far; + if (flag_record_traj) + { + nav_msgs::msg::Path msg_path; + geometry_msgs::msg::PoseArray msg_pose_array; + recordRobotTrajectory(time_now, ptr_lio_locus->getTimestampedLatestPose().pose, + params_lio_locus.threshold_trans_traj, params_lio_locus.threshold_rot_traj, msg_path, msg_pose_array); + + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), "#[" << msg_path.poses.size() + << "] poses recored for trajecotry"); + + msg_path.header.frame_id = params_lio_locus.frame_id_world; + msg_path.header.stamp = time_now; + pub_path->publish(msg_path); + + msg_pose_array.header = msg_path.header; + pub_pose_array->publish(msg_pose_array); + + } +} + +void publishLocalizedCloud() +{ + // publish localized cloud; + auto cloud_incre = ptr_lio_locus->getLatestLocalizedCloud(); + + if (cloud_incre != nullptr) + { + sensor_msgs::msg::PointCloud2 msg_loc_cloud; + pcl::toROSMsg(*cloud_incre, msg_loc_cloud); + + rclcpp::Time time_now; + pcl_conversions::fromPCL(ptr_lio_locus->getTimestampedLatestPose().timestamp, time_now); + + msg_loc_cloud.header.stamp = time_now; + msg_loc_cloud.header.frame_id = params_lio_locus.frame_id_world; + pub_localized_cloud->publish(msg_loc_cloud); + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), + "... publishing localized cloud with points #[" << cloud_incre->size() << "]!"); + } + else + { + + RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), + "... localized cloud is NULL!"); + } +} + +void recordRobotTrajectory(rclcpp::Time ts, + const geometry_utils::Transform3 ¤t_pose, double threshold_trans, double threshold_rot, + nav_msgs::msg::Path& path_get , geometry_msgs::msg::PoseArray& pose_array_get) +{ + + static nav_msgs::msg::Path path; + static geometry_msgs::msg::PoseArray poses_array; + + path.header.frame_id = params_lio_locus.frame_id_world; + path.header.stamp = ts; + + poses_array.header = path.header; + + // milestone pose; + static bool flag_pose_recorded = false; + static geometry_utils::Transform3 pose_milestone; + + // check displacement over thresholds; + bool flag_milestone = false; + if (flag_pose_recorded) + { + + geometry_utils::Transform3 delta_pose = geometry_utils::PoseUpdate( + geometry_utils::PoseInverse(pose_milestone), current_pose); + + // for distance more than threshold; + auto translation = delta_pose.translation; + if (std::pow(translation.X(), 2) + std::pow(translation.Y(), 2) + std::pow(translation.Z(), 2) > threshold_trans * threshold_trans or std::fabs(delta_pose.rotation.Yaw()) > threshold_rot) + { + + flag_milestone = true; + pose_milestone = current_pose; + } + } + else + { // for first time; + pose_milestone = current_pose; + flag_milestone = true; + } + flag_pose_recorded = true; + + // elementary item for path; + if (flag_milestone) + { + + // data to store milestone pose for path; + geometry_msgs::msg::PoseStamped aux; + aux.header.frame_id = params_lio_locus.frame_id_world; + aux.header.stamp = ts; + + // assign translation part of current pose; + auto &p = aux.pose.position; + p.x = current_pose.translation.X(); + p.y = current_pose.translation.Y(); + p.z = current_pose.translation.Z(); + + // assign orientation part of current pose; + auto rotation = current_pose.rotation; + tf2::Quaternion quat; + quat.setEuler(rotation.Yaw(), rotation.Pitch(), rotation.Roll()); + + auto &q = aux.pose.orientation; + q.x = quat.x(); + q.y = quat.y(); + q.z = quat.z(); + q.w = quat.w(); + path.poses.push_back(aux); + + geometry_msgs::msg::Pose pose_aux; + pose_aux.position = aux.pose.position; + pose_aux.orientation = aux.pose.orientation; + poses_array.poses.push_back(pose_aux); + } + + path_get = path; + pose_array_get = poses_array; +} diff --git a/src/localization_module_lio_locus/config/parameters_lio_locus.yaml b/src/localization_module_lio_locus/config/parameters_lio_locus.yaml new file mode 100755 index 0000000..efde4f0 --- /dev/null +++ b/src/localization_module_lio_locus/config/parameters_lio_locus.yaml @@ -0,0 +1,150 @@ +ros2_wrapper: + frame_id_world: fixed + frame_id_ego: base_link + + topic_cloud_raw: /livox/lidar + topic_imu_raw: /livox/imu + + topic_cloud: /cloud_input + topic_imu: /imu_filtered + + flag_use_imu: true + flag_use_scan2scan_matching: true + + flag_use_prior_map: false + path_cloud_map: /home/solomon/cloud_map + fn_cloud_map: cloud_map.pcd + leaf_size_load_map: 0.35 + + ratio_fresh_map: 1.2 + leaf_size_vis_map: 0.2 + + flag_save_map_in_memory: true + path_save_map: /home/demo/cloud_map + fn_save_cloud_map: cloud_map.pcd + flag_voxel_filtering: true + leaf_size: 0.1 + + path_log: no_log + + threshold_trans_map: 0.5 + threshold_rot_map: 0.35 + + threshold_trans_traj: 0.2 + threshold_rot_traj: 0.088 + + flag_arranged_proc: false + freq_cloud_proc: 10 + + imu_to_lidar: + tx: -0.1 # m + ty: 1.498 # m + tz: 1.227 # m + r: 1.889 # deg + p: 12.220 # deg + y: 89.331 # deg + + baselink_to_lidar: + tx: 0 + ty: 0 + tz: 0 # m + r: 0 + p: 0 + y: 0 # deg + + +cloud_preprocessing: + leaf_voxel_filtering: 0.5 + filter_limit: 120 + + size_cores: 6 + size_k_search_knn: 20 + radius_search_knn: 0 + + pub_cloud_preproc: true + +imu_complementary_filtering: + do_bias_estimation: true + do_adaptive_gain: true + bias_alpha: 0.01 + frame_fixed_: fixed_imu + flag_publish_tf: false + orientation_stddev: 0.0 + pub_imu_preproc: true + + + +b_is_flat_ground_assumption: false + +icp: + registration_method: gicp #ndt #gicp + + corr_dist: 1.0 + + tf_epsilon: 0.001 + iterations: 50 + + num_threads: 3 + enable_timing_output: false + + transform_thresholding: true + max_translation: 1.0 + max_rotation: 1.0 + + recompute_covariances: false + b_verbose: true + +localization: + # Registration method + registration_method: gicp + + # Compute ICP covariance and condition number + compute_icp_covariance: true + # 0: point to point 1: point to plane + icp_covariance_method: 1 + + icp_max_covariance: 0.01 + + # Compute ICP observability + compute_icp_observability: true + + # Stop ICP if the transformation from the last iteration was this small. + tf_epsilon: 0.00001 + + # During ICP, two points won't be considered a correspondence if they are + # at least this far from one another. + corr_dist: 0.6 + + # Iterate ICP this many times. + iterations: 50 #25 # Suggest 25 for NeBula Spot datasets + + # Maximum acceptable incremental rotation and translation. + transform_thresholding: true + max_translation: 1.0 # 0.05 + max_rotation: 1.0 # Radians - max 60 deg rotation + + # Number of threads GICP can use (3 threads ~ 3x speedup) + num_threads: 6 # - defined in launch files to adapt to robot + + # Enable GICP timing output + enable_timing_output: false + + # Radius for normal search + normal_search_radius: 10 + + # scan-to-map, scan has normals, map has normals as well, but the data comes + # from scan sparse data therefore may be beneficial to recompute the covariance matrix + recompute_covariance_local_map: false + +# in general if there is no particular reason it should always be false, +# since it recomputes the covariances from scratch but we calculate them from normals + recompute_covariance_scan: false + + +map: + octree_resolution: 0.01 # 0.001 + frame_id_fixed: fixed + num_threads: 6 + + + diff --git a/src/localization_module_lio_locus/config/parameters_lio_locus_reloc.yaml b/src/localization_module_lio_locus/config/parameters_lio_locus_reloc.yaml new file mode 100755 index 0000000..6109d92 --- /dev/null +++ b/src/localization_module_lio_locus/config/parameters_lio_locus_reloc.yaml @@ -0,0 +1,150 @@ +ros2_wrapper: + frame_id_world: fixed + frame_id_ego: base_link + + topic_cloud_raw: /livox/lidar + topic_imu_raw: /livox/imu + + topic_cloud: /cloud_input + topic_imu: /imu_filtered + + flag_use_imu: true + flag_use_scan2scan_matching: true + + flag_use_prior_map: true + path_cloud_map: /home/demo/cloud_map + fn_cloud_map: cloud_map.pcd + leaf_size_load_map: 0.35 + + ratio_fresh_map: 1.2 + leaf_size_vis_map: 0.2 + + flag_save_map_in_memory: true + path_save_map: /home/solomon/cloud_map_bkup + fn_save_cloud_map: cloud_map.pcd + flag_voxel_filtering: true + leaf_size: 0.1 + + path_log: no_log + + threshold_trans_map: 0.5 + threshold_rot_map: 0.35 + + threshold_trans_traj: 0.2 + threshold_rot_traj: 0.088 + + flag_arranged_proc: false + freq_cloud_proc: 10 + + imu_to_lidar: + tx: -0.1 # m + ty: 1.498 # m + tz: 1.227 # m + r: 1.889 # deg + p: 12.220 # deg + y: 89.331 # deg + + baselink_to_lidar: + tx: 0 + ty: 0 + tz: 0 # m + r: 0 + p: 0 + y: 0 # deg + + +cloud_preprocessing: + leaf_voxel_filtering: 0.5 + filter_limit: 120 + + size_cores: 6 + size_k_search_knn: 20 + radius_search_knn: 0 + + pub_cloud_preproc: true + +imu_complementary_filtering: + do_bias_estimation: true + do_adaptive_gain: true + bias_alpha: 0.01 + frame_fixed_: fixed_imu + flag_publish_tf: false + orientation_stddev: 0.0 + pub_imu_preproc: true + + + +b_is_flat_ground_assumption: false + +icp: + registration_method: gicp #ndt #gicp + + corr_dist: 1.0 + + tf_epsilon: 0.001 + iterations: 50 + + num_threads: 3 + enable_timing_output: false + + transform_thresholding: true + max_translation: 1.0 + max_rotation: 1.0 + + recompute_covariances: false + b_verbose: true + +localization: + # Registration method + registration_method: gicp + + # Compute ICP covariance and condition number + compute_icp_covariance: true + # 0: point to point 1: point to plane + icp_covariance_method: 1 + + icp_max_covariance: 0.01 + + # Compute ICP observability + compute_icp_observability: true + + # Stop ICP if the transformation from the last iteration was this small. + tf_epsilon: 0.00001 + + # During ICP, two points won't be considered a correspondence if they are + # at least this far from one another. + corr_dist: 0.6 + + # Iterate ICP this many times. + iterations: 50 #25 # Suggest 25 for NeBula Spot datasets + + # Maximum acceptable incremental rotation and translation. + transform_thresholding: true + max_translation: 1.0 # 0.05 + max_rotation: 1.0 # Radians - max 60 deg rotation + + # Number of threads GICP can use (3 threads ~ 3x speedup) + num_threads: 6 # - defined in launch files to adapt to robot + + # Enable GICP timing output + enable_timing_output: false + + # Radius for normal search + normal_search_radius: 10 + + # scan-to-map, scan has normals, map has normals as well, but the data comes + # from scan sparse data therefore may be beneficial to recompute the covariance matrix + recompute_covariance_local_map: false + +# in general if there is no particular reason it should always be false, +# since it recomputes the covariances from scratch but we calculate them from normals + recompute_covariance_scan: false + + +map: + octree_resolution: 0.01 # 0.001 + frame_id_fixed: fixed + num_threads: 6 + + + diff --git a/src/localization_module_lio_locus/figs/further_dev_flowchart_logic_locus.jpg b/src/localization_module_lio_locus/figs/further_dev_flowchart_logic_locus.jpg new file mode 100755 index 0000000000000000000000000000000000000000..a1ba4d5f4c22b2c05c0dc7b199c2ccd9077e9af5 GIT binary patch literal 591122 zcmeEvcRbbK|M-)JcxQYo8j&rlhcYrEDp zf3GX`_U>KpdcQyK?|;AJJnlK?b@ubD=Q_u3-|k1yacK!D2@n<*7U&M}2ihG3iDE*3 zm_vuK4`Iw2z$SApf3jR$WdIJ!`O$g z@PT-0pd*Jc3HBoa=P=G8Y+Nk7BfA42LTn)RIQDT62y5i^A1VI7@BbVEC>W~UaBbXE zF}@is&}QHkfNNO)pE%7yx%$;44)On|J-EuY_FyE{4>DjL-@8J63Z?*FkXyF;U#vzu zG{U)4$>j7{IWQal?+n&fTrbWi*TTD<=D6?}+`QTjA5N{mng#886rU4Xb_>DrujaO{1 z_%^*TU1@bc9pAxTh46@8;1J5H5@bydH?^qz^vr3l2CgS#OtZ65P&Kr^GFtTs7Tr1f0P6JN~;s1Aj2?D;iJNL{V z3EEJTYhlI$#Hihs;;3qS{u5s7@#II0clJL1`3L*Kyc6q&amho&)`wa>zQR_2js{_~ za}%@kKcNw&hAn&-^^b#`yjlgk*$D1>8|~A3nNu8W53Cd+8hO?qD(=3LTPGw^!$sJMQ)g|E5UT-xkKzDT3-uNG;cf zAN$bJ?-TI)Z&Uw+$bSR(Z^aWXw^c4r8s~)D);L}%(M|e(f_zK(Pd$VIy(|IK&Mh|7 z;Szg!|8BMtGmi+WA0EntS&9C83zvxzEys7A{;)6v7q+70{iiMdY5IRM?AY8_a<8~( z3R})r3FS~2Hr;r+8OMrCvDBvfzc{GvNs9TnNfNS8i1?p2^B+e1qiNGZ!`4C@79`=W z!`zKvdr0l|4=elaGOuoi^z+o;A$wB7ai#~&XOY+Q{ z1@mp+2q0V7xS{&hp`MBf{f2tkZm$+%in3Qcc(x_#%0zv zhW1DhwV-u5#1%}%jTn>74D^X($$FoXwOOnotj;Eoq)ze49GP|DzVclVA-ogclFIXh z`id(D%h{oUhX${%qBnRe*jKO(@@nqIH_}usQ|YF-i#thTCc-u5+bCg= zZCU48=^|RFPal2bm(mV#rf=XE=Qaw9Dho`TAYq1?vbx;#AvPY_k(5tTATDFvW?!rQ zO&6~zP*{0XH+RO(Q%=Lv5{?k6tF5EUN4fLO2Y$gKbX3$HbuG(?JaqL_Do;7k z;-LgW%lhGyJ3@LhZf4e-bnM-+H4{4=H9+l>RXYy_y$-bcH#TYP&uj2vb*9-_xy0K3 z{`0c_NHG^IHVQrc+4A#o=Xx1fYv9*`5-HvUY6`(yM=dJCTHq)(mz#;a6$V&=n5c6{ z1xq1r;+n4}jSD(j`ZpR%wIi072AjF9W5YV2Z`GZp%XTswX)$(d7i3)zWcf{lV?AF! zC-X47$si{^BaAmy%T7Swv&76Q!`~nyA-Cu7)TZWC(;%;KL)ZI4qktw4nuj^_(7XL* zw79AEt0&HCR`hwVDJqk-G%tp7*4Ssd?nqY-asXk)8xR)0PKVIx=OreznyIXj0&=1& z$QVa=Ag+Fan=2z$!ldA0U@a;$+xF6D z-oXHh6Rdgn_7Y?FjeZZF#$!4W6&_U==jF?|-f`@KlK4SUQ-HCC?bwKlk@wAY^IC|0 zxM>dS0P04{q>b&3l+i0^X#z4zE|;59fX%|W9Y{O9Fs1&MVQ!A1kg66y^V$gct~>*_ zM9;kA+B%~09t@6M6T*^a#0kX8v}qqTA!*%kit@<%7%Y_5w44PG+xvoQp12Easo<<8 zA$P%U-j%*7>@{Yt(_c8~hn1@Y0AB-&I8!f4e0bOij?*6?MDzUTikMK$r8O0{2Nrl@P? zQ&cIb^7sv4OZ#H5Kdr&b)Q~Hfl#k7 z_)yg05uO^_0v$^Jc)rbW%rKp%g}4JsXldx;tibg|H-Bd}^H$!Rog6smq8Ey1NjgF{ z(j_0Sl}xJ_=lRC;sa~BPjYBPKtbEENT0wc9q(gaqMG}*Pq&5oz+m4qK<1~o5sym2qn{6+6e zwblcT`Gt4A+GQ7X5vAp5!w-3f&EzhWiXkyjL!$a0yLceS{u9Rve7O&+Vfl`BR>84_}=Z#ZE_Nn`4ux*eHx zNk6Nzx7o*Uh5pKekGfc^WC<6N{ScI}eUA{<#RBVMOMJxV`h5`;uIU=CT?)wKCwE+vy*ckFArAnTWb!Jfh&!0SwmtP+~Q;)Tz5_)@fi5JL14H+kc?!KP;Mv^ z6@Fvy1o=`nlX*c#N%s)Wi|i5^h%Wdl=IfCTfhe*%W`6@RJ}vP;^%Hub?{1G<|IdMK z0+Jo!@~QYQ760*jnBd&13GHq6@@JfD3I%HlzjfMhabj;p~<%_ zFTCe}x`Ie#nJEI>w=yVa)-YlnRmxiEI>%T%+Z|@pzm*r;y>x*MnFy}Fff>I&m?IhN zkJzle_T)Y})FmIg6*(M~;C}Cq+J7Gf#foz|3U{65NORR~lx&R^E8Tn*LEcSS3i>%7 zuQI5wY@S(8Z~<%?E){CG=&b(PfmR6|5-i z)Ip{wbL}<_ronr~6QqS+Knyn9$|=C6ClEo_za{+YF;shkP#2eRF5eN&O)LhM$=8T| z_fTa+en=Dw9_)B-(o5*qs^DOWzp;SN zx|ff8(}UHu$LYzPZ;B5qop20!^pk*%Cqn(Uv7>&AoQreZ5DiWCuo9`P_uppuQrHG$ zNFBAUqzU@b&ejAI11yq3G`#9y+xPr@)Y!YA#4MBfGNNED6Yt!_5+awe?^9is^KaWW zg?ir5GsD%KDn9*rGf-Wkzdko2$!v_0r}f5v;PAfOneW%fyIDujgSFKq;|O+=f2na} zXj|YwTYiH!!-|gNjgFzY5Inirnp$FaB|@{%Cz#&8+1L_{~Wg$!rsay+1h?gPIE90`<#8#IhSEuE#C|6UYH1cb$dqb zZmou^H&Bll>G5v^Yl-iQB_BV(%y`$*knFKnCVe3MUVY9Uwpr<*0_KK%@0{VByPFE* zrpG+rX;XyKF4R*z2N@5RjMPdmEv^~KKH3Gv$@u9KDEI48N{ke;tZu=K>?JaU13gS3 z##5vxyF=;>3)KQQ=eKb$Ke*$ZJEJyLI@QO+C4M5=G^_V%T!~9b=<^R28YUqT0A4yc zup~w60wQed*lL?HS~l%ofK*0k%uQm)#B1 zv#$oLv76wCqv3j!Fmj>*(amSjLy_BKOh6bvRkN)C#_$sH!f&%i-ZQI2bMv_>i)5Gj zDajt!_sm6<+hncs`wSva+~ZP~Udn|ybT+g$-6+*5v^rlobS2t(@@o}1&cS*amk=Y2 zvyyEdSy)jY=4Hjx%_{XL5(*YfsMvA;6GzA~GK|l4;eXnAT4kwPX*_g8McA3TY5_ zSQBlE^ckTCaVlp_6a{Z~lG_X@cT?n=B0}BZhz&+_ygDBpJ^C5QkYjNmFT0xKu~?0L5=J$~kx z^FUfC65-|i%y)71jx!|32`>VKg|fl3a;hu9_L-)2PXK05(~wBhFd+2;W-J~`krhGS zXf>3M-2CIL1A%_U(<^x6h@8A)SRD0Sp&hQ)4-g z_HFXw+yZJ#)#WJJ8fz`cK<2fro*=}B@%s6o*}H@N_`*&?M=Re^A?yU2<$_)pT;@GW zD_i4N<(cSC^jPVrr(fP@zV)~c0B?2O1sU)zp>GQkt_)tUESWsnTTHuIP}C~SsvTjK z^^u=VviL31Xa~9Me=e@A6uq;ea}+Ng)N+iyg$Q7R!uFY z#(F+IXDJ!T(Q*#kCx%s{Fog3g6D(Pz19im6{W*3_OKQp2=nyU8%r{;lUtLlkW$P{6}9y3&h*TTjFfzrzhGTx;!^G27c+`OBKv3Q>4&9#O+F1g@7{65!W0aR(OMd>L}E$_gw$mNvOZXM_KD`4 z2y*>^_PK9}8=-g6k7gzu-)eA0jx*d({c}Tfh0$oob4u&SDbgo$?`7{S23u^q;SGIs zSiB&?KN2!f&53vW3c#5-NJ`ki#Kp#6MY-_D_U$$9%g?V4M%E*;3y&rXogOlPC>oNS z8`?W`*nk;hWL~588W7IB7)mb{!(%Z_N>-;(J~q@reSf8;!X$W&XW)_j`h3cZT~Oni zuKN;mD5IesURsenf{EvCcbEk@+chh?PbFY_g*E0f@0J!?tulloq}W2< zN*+p=IbY~|pWFH+4%gII#zDgkx>?N zrWa`br7HZihS^>R{QH0sg4)$6c6Ml)a&Khpj`gP8>_daG6KrfP43>pNs{J<3ZkwN|Vkb(AUQ=%tR(GbDz8xcV2cQeaoMxL9-yOnkMqI;E2w+4Ds@~#?4~(U#(FECB`Z|lY+Kx!OP&0@@nsTZcXRaFditQQ}ofC#e`m?|o3*}L~Dm$^hGiDd# zb&ycQilmbr*h#8y@$o+|*%(D^<7Ui()V6KY;AertwC8PE&gfiR^-wJNMElT#jLgmS zMyO`KYLZ10RleR>HW)=!{c1<>5dn=KmFh0mnmS6n@lRkizm`!aj|F4jRDsB8xj|X;KZw=MVSR$Y(0JUZt$iRMpmpZ zsNYwumAZY5Q$2!*GuXp<$zsf%c>0X~T!Mjc)6kOUqo(eA+amgtT^At%|AE5-v+d~~ zsJ%*CNxW2j8{e;Ht7ABDbn4F6Ap+cA$tH|MEFWDGk9tRO9ptBjp$B-agA&0KAO&^Y}js2*Y{>cRUkc zwEc*+`$HrTIFh@m;1(|edK@Fyb4ck%xM|e0i6FRqSa4NvSj;Kl_&)~T1+g=wrxbj) zJu4S*IRmEM*j~!LVa{XPT5(&r|Ay6xQm=i05LR{xR08ZF!aWuUps|O2eicfj!oCr| zpWvW_jZP1nOLSWs>sfXum_BnL>L0-LTQ2M?b`^j`TaaSKEmu9doY3Z54A$>cFaWbS zeoOHAVw@!^mz^cXFfOsMq0Q-#XTO*3OF*j#M$%gKBy4GA%U4I-gtElzTNU5WP6_vW zTo)HT`Q{{zm+#&; z?C%3+ywH|`giM+(Pq*%m62q8ce}G?ps}1kmF6f%@az^mb{J9#lE-c~p0bjvChU+g| zH{@PlqbwTHQ1N_OIO~4!2AyazK`!F#SmH#^=dnb<#aM*+d)i3F6Sn=kAbC=T$7LA1 zi1#E!OzWGS;XlbHeHLTwhbYJ|ocO~U@)YaO%Sfh+KAQsVm|Unxj}t_5!{|gd0Q~Qp z`FC)o5dz@qE8zk$O#u`VAg{j_x9|A@cj!b>Fu7Fwi_UimZWRz6cFji_`At0ugfNri zKX-OP+=Tkm3Okz1=z3cVyjoQ6}Jhftp3D1CalXSS!?w_ ztNqNjDZBW7gQr6zR%TxKF35$$(9CrCLAf^dJO8udUe{t#7G#mp4t&13f|6@zh~(88 ze6BZd>N8zIoL;K5h*>?C`EWYNB};fkeP`QQi|Fn1=1r?Dd;g2vad6RQFVOc`)U+ht z(kACMc=|!W{Ys{jKv8}oip&C#$1qrm2Q29;SM@@nLjrCih6Rmj9o)!FCYYOG=jS-L zwQCO=)7tHU582xn)ilP(S1ik+jcH&XXu-VV)#gS&4NJFfHC5L9ZdJYf5#Iha17csP zozR9|P@AQUU$ClsYjP;FPhm+G)SV6jEr9lS>KnxgX{c;Mv!M3tCYdbU!hy|DQUgSb zs=m@FjjF1vJjy+8nknvPFOY%~s;Uz;Q+x~hNhl%r9`!Eh#v&{sw{5SdgcV)4D!Swj z3OBIGr8(@V{-y+63cmg{oLDT?JHtv+qa+7yBdN@ zaPV6+?(Pxpu|XKZ9cxD&`Gnvw>pZ6CU(GMEq^CniTKsvBD0vy|JmY^V8eT6k$lbu= z_}t|QMlTQI;?wj7U?5Tc)N!)b<)hkg^))S6RM!Pkiar0^KVLtN#kJ4yVRYIRFBqh>l7rrfX7imF_FZ5=Gi zLizw+Jd@bgljc^-Ju`o)$FhUo-MQrmzWW002IEDcp<;#N&C9?^cyLjH09M&JLQymw zXyG0V0pU26l&2tC*h0vA#p~;$Cnp$k7O<4RS%@}n!36v?Hgn_rd1SQHl@ zl5&(|TFcNu%5FY7f=l@(mx#d7$1nRjg@VL^rdpfS1%T?0#)J=HZTs5MS@G zqoV0tG|~=r-aYuPnyh|WI5A-aMzja$TVo_z|G{1jFk?6~k(4VcZq;`wBXl#K$D6`# zS}d>YN|}6}Vf*fZt#XMi#MZa4MifRw_iDW0NR`)K68+&sz}l10H;sJFdZb*@KSeUL z*WtMiGsA6v?uKYyZf8Pd0BL8%RlfUMYjk6>Tj$C3oYD*2nBU0f%BJXp1Cw(ggafcr ziXoc|##{6wE)4Az-fhF^QaKx!su4UN4;8;ATS|v+SI4H7j?Y#-9#;#jE{>fqn^+A~ zuuCE?rH!fWUu~xXkLiaHunoE`ayv3PoDJXfl~pK?4bdx!a4$&Cv`^G2gXQN5nD?dzSKd4tkVAh?towW2*T2(?{XUME-LpP& zqR!iJbL~l{r;wB8dzNyi2?I}4-_lvNO7oZCG1kMzBTl5YPey2GxH<&% zGaCChOd9JF`bM~+dR6cAAL~v2iMT{vwR64dkpM+GQVUz7X76MF?J9RmUvWU+qlrbP zvn@T#$jVuI=3kk7cAoJ_MWYDt<(GjH>t)Knq=SVQUbt74(fho{{?1{;V+@#OsX;14b7Q&dd0IT zaWplXNeEdZxw4x!+#Q0VscYv(M2W8h=%sVIvoj#yKRrGl(m0W8J-+cEuB{sw8o>OB z%-O0|uD9HZP(D{96|zKmEAgi`aUdqf9Y@d?dCj8gMF-`rY%qOt<4boDh7O_(MQ;6z|rAd=I8V4hPCAk&hvOCAa@_}9&D^xQx zROe1NG--5Gp{wcGtpIFoq^M(B4Zh4l#2!=jL1;agM-aEKjIb5@&RsQoOB}yf_upab z*!=UtTiXsFO1H6A&;+?E4hb?wdzmml2lm7TOc)Ej3sRkvMexy%*|}R`zI_wm}z)m?~NEa|!+$ zSP==QQV*4!^*`GNMZwK~nC5G4(KuV`BsT5@YD2kJ8roL6bd$=VI^qv*n|H2%5fA>I zAe=a|tRYC>dQNd{Gf?wm|4ixp^d%!{mJqb*LU-QRp8o*vvWz*jRsA{q#IakjwXVj1 z^~EimY8AYfgKMA29dty)NU>_SmPVk5bA@`0m}FDBOH}aq>cK15OJeX;R}$0JNbRdt zaP+yWMS^v7mk*_GX@%ohc4PUFZ7bkZtDBzcUb|p2?%XOe0zD)E_81qkXqt3SjK4Y( z3luRk)|~HcG3ioqHl0ZQaVhftJvJ9MSY0n(*tP=6hm~q|0=jNT9P81tIk}PR&&M)# zRJn;$+#i4K3*i2m4c^lBw6D<0n*mEYH@`g5_srMKxJDx^w`QH)2Uct=!~hZ17ZC*} z_MG!s-Xc`_W))p|CFS;)^gp1O_9C!Ql^dibxx=bc;YVY&Kh#&v$h%z#(zvh38p#sG z+|6MAe9H??NlIoSvJ-dN%sV-I)4nfAhSRN6iDJ<_^HSqk=<6>P;6hAjA@(HvK7Z9K z`jX%WzrQhqFYvGo{CU|*635ciT;eB+^#=}9%q@|>*YXlLQEbgCC1pLAqva7w#_!Yg zj#2ZcSnD^8cD8stAt|a7Kt>ITySO11qrP)O?s;ci_B!zsK`xy)z=*5ox>jG6-nJ3m zIw@MS^Q zBM>7eV)>H+qoKPXv858tT~IOy*Z8E~Bp&I27pC$98y|oIxP)v|X~)j-K{9=s>3gNo~- zOISFw3lZ7xW_!VcV58m`(2Mi)#Gm@V zf*q#ws{-}VJKXefVFLwjkxW^5q_H&VH9Y?pb6eSLe{MJ0JF5=rLX-Sjj@`=Zs&C^S zPUdxSyPRAMK+F*GM8CE&yPG52sj|{vC}(h6@6EuIie%Tzspafgy)9t9ph(w8%Luis zG-gH(3A7Vf&aWWt2HEC7oxNe`_%6uM4Pu)#I?Kk_`mosxDDVIsLz22ll{M}H^%Rwl z2V#E6etI+k5BG?6c*Y95w{eL|Xn+O&EW>P>g1nJBP6Uw71N)bs16AH5`pQ$qy!}7 zGJ8oZLdhxUQo+P4k0{&MQ&Dgib4IdVxSE0$E05Hy99pg{nLH z@4_>$tvBx^Ilzvn3gf9Yg)~`A_xP5%(8p$ztK61^%rYp#J6S9?FPslAVQZQ=y#DqR zv?XQw#51U228pcBblO9MUf!QQGs6S+K_i|&i;r1ECS?t(rn zzM9!yv^Q&iFEq|;0((d}EglX6(LIC@X)(HGBblQx z=o<@^^SkCBfVQinRQ0h<8GS|=WdtQ|MVHUKybnoOJO-@yOh23ov>wOl)nWf&6m%|a zM2&XhQc8;FhipC=nJMu~+6S|Z6875Oa}BAH#tW7~QHrqOL}fTNKmnsv>x?H4^$ql0QI8#?tU;zj{|{7{+k*|aJ}oe>3j6V}94lCb-K zVjk}`=kI@hNxw0coQxtf2RL@A;p|LRQMsy;%_a01;laU)sY5d*+vUTKz!~|F{nu1y zXro*}n|^pVmB;U>0*!wL$DCXyx|AWYBw@9B+sJpQW{tY!Z&O*?CjeE=`(fmudZE{rm{k{ z{XMY$8v9EoSIFQ|S%03#N?!VE&~e^Ady}RITOPUvq6&EC-n$@$qqv+SB!G5N<3|SU z?Al#WI!;yc>J2NBt!gBwVrdtYFJ4Fnhxn%i)_zEG{S~MO zzx@9EoY;^U5vWG=xIB3QZK}`ges_)8-NaW2#?CljmrAem-d#LTLX)T)|_OR2Kgzm=zV zt+Ta(iZDrMSJ^^#K{MH_OwyU`XLEZLoNQ=ZD*7^*vMQgH&&4E-v~q+*#vwLD_th1D zz%u^Q#V4G>W`(2FqiFew4I9*C;Ke{Z&Hl!2vLTs3N?tCov@JL}sj`FGnZA9HF|;L> zo5#vCSl2ip^xn$bU67|*v;B3+X9t1xTmD~i5Twl?O}vjf%y|8e;s6<5dGtsZm`Lel-xc1&!&i|ij<6q;>8ah2`T+}Ff zzoOM<8fJBKv!eI#wcoPvWut*TRN;?4|J?UWg6e3?v*^CUJKhXGFXN9G+&fdNckGsV zs5VQ4v)u+>l)(Rqa{MBjKRefWd;=x$QzN8F_`8nown1jk@m)}+u(~-ZO`a z+^A_YYBga+;FgYV)EVHz&1CaeR(2X?!|fb6M+l$TiXyH9kgDBT%+mU`VeE+>=rt|Q zY^dMO(VCYdyl|$0^bH9L^~*Y9rv&X78w^8%3Y_#I4;yk!8J;{cNn!`m1_m{rau3A2 zjQB%t`@?bgC0%TL?-CD7AHDPsbMJlRtHQ4S$mSu=@x(GGP@Tmk)ux=%ozjqTB7iHz zsFP3Pr;hs8^yG@dG`h((AtG%`VGu~H+G%GTog@*_c;)9#6NmAj1rBK*an#g~dvD#U zj_-T{Of8$Kv6VRb7$|r7{#ND@2X3ucw4Q4H?QR<~ZY}Qsb^5;qnveJJ!@Am(VT&!y zB0xHu-qoL^{8|P(7;b2-b9ql9q3RKrC8Ya}RkRPCox7|9DJv(YXU~Aw=zF^~a48Og z?U!d5U%{y;vah$)4(9ykrwfPgI8#CS6;p=}!4+86pT)p3dztLyG`cco$_$nGzPHL- zP7^xvH>Shv&ta@PHsXutXTL2&GEG&H{)%{vZC*=&e(Jp=Pi!68@ucaJ9Ub1iKRBg2Fz0z&t&8?LntInXT+DP(m11W>N;qJ$T5{bw&0VaSt zU}q>Fj&5H6)_D+!h_a+lw9Kq*J;#*$P*t}K&iu2wbICC4(1O_&<3YkD9z|7Qo-!I` zEwyp83b)S!i(3=;bjK+Z8(VV;ixMJ` z;CJ@3sE^ln4k5;rPp57mabn{&7SC>m%37$Tf08x8)Je?Vwe)d5QEAoT7EjyQF319F zV|1qAGJ-}%u<4et5Cp5HVM*M3y2NQ15>}|S9XYem{c5kR7}RS-@kaW?@M^4amnuj- z2jMurtb+i4q*l3chx^4F`Kmqd)gHct?_d3iCxUE&7*vZ==wh#(r?`lPSn4#UXKzfH z8nK66rAi1tl@~GHMVD*7@#&LC-3No6q}LNGh~u7>hJ#NU+6V4?Bu^L9>bpLTzZnHX z66mEOyKk9wAz8D{m>!*a{iy)GRG@u*gluWyc*qK^mS63-fzK_!#2SeO(3f_K0`06i zbTsBw?7-;pwE8d526U5YA+AqKwdRmTHK-=y4l{6#az$is+CAqEV^yN22C|0UdVG>> z*G-!+?TozA0$f>$yYuqpOV}vU9t%daP&f#S zgofhOxvh>c5oYqY8Z&8U4;879^VJWI-zZVvmhbbYzp2`TR!}WkMIV)gd3vbqf_z_m zoL!2~e>);{WHWz*BtD((8lnWPaBr$a`Myf_e6~q^S(VTT)3Hq0)bsHo#r{D%v z_;(kp&1}~AJ!_U$&UcoL!0OnsIhG-mYZNa|#<=LXJ=!*g6zPRqzt&(6zGVB_4aUP} zxUpPy7CU4^7!LQmdbdjwJ-X#yRT}SHrpT*ahB0pp(e)J$}awBojSfen0 z$2HOXv`uOl5&=zGSS=mO4GvRFop_5%=!L5xuWU+tg5%ft?^~Vc*Y?q(rc2oc@!amr zMK+-!Gr?RT7b7rmRf~|$M z1b0CUkTkbfly3DEvj-Hz zvdmZD@WPl>DZLZ3l_)xXb4Ye{kP!8SC3zcKQK0@*|m6y1JKDe+js`pOC$yFH}}pe&V1 zzt#gjrJ*;y3!*#bP?8mMwLF0JedyAp8ozn#5Z~I;TbtT|64Bt)&Op8oo@u8Y<>a2e z&$Bn^p6Xw4v05VzR9j+!yOPGLIaXy`t>qWdzBWwtMm)plV&Z)|BG*7^JHXw|5T2AA zzl0~F&d+3iA|{{53L2O36sF#?rvh9*T=Sqjvv(0S{NrG^=kANoB(t2Xh;k_-;h1ILEdv61UiV?#%mxi zM^GLv(;)A+cUw*1TsdTrz`1O4ie2JwoV(lQt5V@{bJ>x=Q05Oxw%w9Qpc7uu(N3Qte1PTzay*rAUbTddOSd=pTwXzeuzAKQO ze;1_uYv$ZTg{ArJ`#H$f1vgXyC~57%F6elCV<9>=E}~0eARkbiIc$6(3b+FjtLj#G zR1u{Y+|4~Jr!KShmJUwWp_TCb1oT$cbY7E`YR>C+u*+Q*FX4I#OTBsF+W^C0JeFfA zPD*UPec6mNL1`#bKfqvNHudhO0)!)Jt<+Fb@%jY`Se_$XAlA^~@jGn?h%+Z+P<}IC z*LI)b$JMsn=hd<=CMJ3+KTDYb2wNKwQwiMHy5Dg@Tg`;jGoy1CR3%33@Z8~|S`+Vh z+C6R#PZKJu&Y~}>u3ZWyz*2e*Y+c{Kx5WC5O2@x%iNvV}hQDS~=QbuKh#~DnvUE^9 zhmHyDTLf2>Je8h-*|mblH1{qS4EvmS08>EG&&1x93G?>3&%EVFa z3Xc*Qd9+suMq?GWh|b~dqhSa5^H?nlC)eQD{5QpDzp)vyUh?yWz$~xj?1HkmIZ@;Z zX+~eN0)i~y!i-y1(uQy{6`vHs+hwHdwu%%h@-X}L{S-KmB5s$CLv7vDA~;$LU$gDW z8oG7zOo)SKvvv&AChSRgvi6m}K}4dth5^@e2fSbzjqp;%Dhfp;%?tlb<0P{z%Cy^` zG6}>j7gR?QrMp9v<=F|>@F8mO;AQWN+)v}n`IPN$<-MFL46Op5ZHzompsh!DIVF>? zeR5EiFB3~>`nmjezhQS?PW*Pa|0fexc0u{FVfPlXSD7odZsu%TOEsG@WGJ<2wT6(R zP@So09_d=<2{$@tSp(o^D`56mWJm_?hv4Y1+9V)oI&H)~yuE!_%$gU96H|uF3#bl?J|iAIKnw*m`A0V>hn2Wj{O1 z*mx{D%L!P%cAd!^S`Y7LW!9 zbFUon&{Y)OJ8s#q;1Ks-ed_uyo=>@4h=<9>u^QvlBPz&f=a?nh7WZZfTSHM+_ZWV? z*<1NA&KF&Oumtwcs-G_~*}RaxLL+Ym{MoxEIMtu33~1n;#I64Fey%FqLNxzc&;ENw zeUZ{);MLW*?_Zj+b;I*~t+n+;k7PvqdSMrV&;_}|N}9&9tQ=p!&k4{G%P6Mu+i1#p?&Q-Qj87lg)$*x#D|J_>>k)-8(UeQZMJ8q_+&?;0gZ227S~MEX>~B^ zaZ$$0M!_`o1%5X!fL2|^6@5%Vq zOm|AnvAryNN=X|}XaG!ffkG8prV6dT(?v%&sIdi?Z$>hh-`;x%22(g-{Fxjc-1Dg1 z)Oj%6$!=9d`r`BTG8VhdSQm;?Q145MK_`aok4OgB1Ny9c*$#APFZ|t$nMMF(KlOc- z7~^$o!BXaKbrtV`($MH~?r4}eQTV=!`C-YRf>GfapXN)z+iS;*Iu_u@nbcVuRZ{zV?)VbgkTjN!VzE#U4ly%=Qoy_fK)wnV^lMdXE0tU5)D2hrW``WcY6U?oKtC1%VoIlfuYqT(i7NM=l9C7uMVBO zVhvxW_(*#XOJkqG>ta@33LTzv4*c^0j)bI6DD>gGYFow)3UH)WOH@&^+LxQ8du&{!(G^Y{|nmD=6C;ee{B3^aMog%Iea(lUWd7Ci|%-|IDlTMaxw}^Xz_QZA26X z&C^{=Hg@iu=WDi1`ePh7E|*870{292RZOK914zwlrOZq~FLZfU7ex~q*Sx&dn&{L0 z^;!pJAofh_;2X(#JVnv|@1F44=S)yyxF(o{-@h6pdP;zUhozNX`cOQ0qgx+%BL>fL z8F;3E&(4$&c#nwvAR_Rkrh|)EfX+cUC*zqo=CT^z=+aKC95V2+aVcOiHYY{C?Ucz)X+1e)pRXWD}H~hm-o(TH+<3T@)ab=q@v2RnJJ^hKl?EtH%O@vZ&IXS2ZT)b#X>;&!k=73PP7SvPATGK!Ha+`*-hQzfTQ_RTw6TU)RdRcNHEV+v zNF3Li3187Y#Q)q`dKZ+SSXRS08`tSUXPGQ@6jhzL3kpTnTp3gk^^qORZ1JJDZy$5k zjY2X5WvEEn&}%G9uk2vTm~N~gMtD8@Lwq$q<`AXomS;|`>Y=pi#_Sm;EgFr{!rXf= zAU(e8#{NO|-ODzbrz1Z3PUi%Xg#Dynch?kbo8P~hC?d;#SM;7eGeU(Q%GMJ{tk!91qG9?sx zrVl!OH}gibA*nNpNz2HX6ZW^-<2h?3xf*Yu&Pd`J-8AORya;HUi~h_)9zjuUe&_Lb zL3jA%asW>DpU7Zf@sT%@ey$mC>tfmov31t7)yTP3Dew1dYW$6kC8^pommN!`ey1^h z*YIp&rN7F;{!$xESehxR7>U{~CqYFjt*j<9Lm^ zy*U8hP>9+jzSPt6^~w#P5EgcFZpYGrdg#Vb)~AlkS9gE|;fpya2m4@0!KDSmIujTcY2?C#Uf~-#cn&46ZUw&9IWtiZ@^+6J92;T1ey1?UE;f`jL~lY zB9GXUo9w0i?hWW74z9PTyDf)E;+b%&KW?_ldlMCwlOiRe@N=a2Sxm|ZD04(=GoR%{ z$NrZG5C99q;>U zt?W~bZ0{?Ys#hbMfW6i4(yuqzn4HR@tG13_0>Jx1{fEv*$M-kZc`3_;%ks;o)blWv z_d(liDMoLl?U-C@bDF6%p^SvHQ~Gc&rtAIGLBYFutMm;M_L87JRGOS_s!e$MQ>VUE z-)3&2P!V%~2-sz9m8Exz(}iTd-(}wc^N)P6JpRhyg37>Hr$wUg4d71U-oOF6sfxn6 zB;W>Vh=m_@wG7;~GhvbRb8jt6cDCtc7U5AoKkjDtmJllNIZ7Vih`l@q9+CKOM-s{~TKL?QlTJ_8&!;`0@ zUs+68(x!&9r7pwj6z|3xPrRZYKFHbzt?$6uE`HbrZDjnB-PF&!nDs*x_QtbdkhXl0!5D8CE-)^*lv8dP?689XjnqGk%Im1eJ7{! z_-b4QIUipJ!*j9xA}zTDazi4YoG3%9wVPks3di@(J+|#C5vXJ3(O)C4P%AG)HtEd_ zH#-Xx&P)5~2)?`yW0U#tYKfh<|Hfv6qWLJ_E-2fTJxn$~?6CnPO^`1TAi^tgUOtD$nxd|MeOQ(xtTIsQG_YCh zbH@KfZk-%n7pS9{CyFZs>H{`x$MKkV8;6L^z9+UoxWs^d3lX<$}i#pMXy0`x02K4ug*qz;J_Jv68d zF0=5-64{{b+6Bd!Ud#7;UYJ^C)_CRVwW7%DgFY%ZDcPK3Xw|~b&B7!Rc>-4R`uO~-T!Nv691lrG ze9N3~Yv$+7(2MIHW|n1)mseS(Mg04XrDR&)XGqz%?^AcF80zi}Fh3NcvK7~NK?2Y3 zIFk|A3F%Edu4q};aNQPNmLasoee)KgqTz-hXIU3E+;;}UVQ&U_yM!;!I&G}A z=dg9ifs<6`d)_(jjH)p81Ud9s=IFdfC%r;PkQcQ4Kla`Ntg7u>8{dE+f`EvC(ug39 z(hZ7)N{DoKr*v(Q25Ce(q`PC&NH<6~NOyPoEo?dG=sEXyzI*TU|9{*0u=bv7&FNZm z%^2eyW4^;&Zdc4>`JwVbpt6r>{JxvG$d2Cd&(hIXx$%=9%V)VU^4qm$kEbQKII!fB4Bs?X*vV? z!ujXLm>0fYg$JYZ&2#he4^Hv>zfuSO0P20J>)W3n6`ZXKNzo5OO|Q9u1&^+L(Fz;A ze$T)9aWG)U=b1R`42^z97f}}d?A~vZUe$Ob>DD-R+XhgeQ!D7|-9M(tvJx|xgv0^I z2D5jjr*IOw**Y&@Soi&euKmR2Yio{CMIShgIPvEYX940_6h6w zRO;dya_EE~hNXOM=8tR08KDJx|6JbY-}9*dyEL4D;uhMOk8KXHqdL4fswO9e9tS{R zn1&TpkRhqkf7M?L9YZHg`|++R=q1l3%0qfq{G6-@AwX;ug9@{(yf zFLy@t*RoJyvbyG0m&u~EwmG=yQeq1~Q(eH!9qHA(M>JldZgg!t1t*Qg(6!Q6z)5P; zmuosdZTNQ%tSgcLb@eG>^NxJg>xnztj@Uqapx;@rzBTDjCSp9xN*fxg_2~Fky#F*! z9oy}&?_cEG!kK`Y*udnv9a_&cz>gh``pJW>*BM)Z0VgRMz0^F~{GB~yJE?{zslpIz$`&>kTq-6Y)x`=-{*vybE7XWBx z57$!;*ducn`J*G}fyk>jY}7wv20yTr&Yr|1*AyL^C6L?4{VX<|ch-xz8Gb0?Vn7lq zvH$?8^gm^)J}C!?kF1M5A-7rwxA{V1o7>?+yx;3s{X2&S+-Sg*6Oh0{?b*I#M`bQz zL22+32=s*Fx3IM@ZaXbh`X^4NU&k15{30KJhR=WWdb)P$BS?taK7_TUufLvqhm`i* zVsuV{4ii%Ksr>z5t8S9ap$GN)ae_~{!Y6jF`w^Yl7}>v0(5=myR|DkWD|dOrmaj5? zy81`m?tFWbWZJ3oGdl-^pGP+|RE%fjTb`u@asv|`h$zq7+H-yz0-G!L+j^2s(}JV} z%lQ&5S({8pf(pDSd1V^~G3_J~>6(^w;&PhA+MB5{)hinAUL#V)rF1`Q=Xy_34Q&uDy$Hcwty7*JfUFi>(S>lT$pDX^od@?R~ar^?5nxLLuG9 z*?))w^fJ?^o1n|p9Z_G5RR3 z{C269TFb?Sz3C@S?c8BlvI+IZEL?{qJM?FVVd_717{-Z_ZX7i($q9+g)hY|n z;Almhn5r?aEUG!#LvKAQ%Bm{Z+W1hfze-XpURDu>(28{Zix~LD$C4t^YyJq)`(exl zqu3=a5@3nd*)~o;;=cd_I-m!4yeiXnf4Kt~^$PW~f+=6)oO?Zf?vCGI^SbjqAiv}G z;rag^$P_PB_3?|u0{QJBUQBqtiT7SY?@o$Dc{`4m6y{7uTeP}*bgVuHk!6;J=+K(B ztqokp-Qqml-<9ab_kldgrQ$ZD%gvH^nr8HPp&29o%0lb zu{!_+#}grA4v@vVy%CBo_2jw7`EzA{UaJ5$44__s0%?BZlO6q0NO<{IKd#UH{rv9_=2trh zhPc-e`M1{-fP8jpYAHHWj|$p9TPcVRzg7T{422$d?C=51>_2N(KkNYcrREHRRmu(y zuhJeuA7I005b{H@&v$UWu7CkKQ4+dM(^=bwn~xplVQVW?Xy9k>xkWlqMNggWKJwHV zeK)`JK86CQcWDwl_sAd4=L2w0pYI{|+ow_EXGOQ`T?gDEmv8Q>cy)JK>! za^Rf^H}=9r)L`J(-Xh*U|sCBo#a7}(@oV@s#$aB>Po9F65He%`))tMXt zf?w+I^8DY=XG&Jhqf1vJ$vU`@i^1&$y_%XLYDd8h*k32C@6p-lZVyQ zcLYuCDhsFkuVlt&l)Kn%K1zm?Pj@PmxB&A4cgXK-3~sGWrWTn=8Uwq3&kQ&_aXc(t z^L`WHwgLC3iRB4-{SLGrCV!m2wIcVB)zi9$hzmxdaV@C+W?;VFCE&{Kii-^{A^G7Op0 zlLOme>b&WsCa5N}Z>4_Wo&-RumC|f6fv`;d2PfYBx(0*W^4QM;AhUmi;S|3xMZ^vu zN@d>%m{VzYQ+R%LxLfEB!0nVgZx)#U5j6U3Bm&;C#Q5}>QKVnn;)kO{B#o&k3n#|7 zZ+4Uj~b-(bD^C(KMgC|v;9hys9( z950l{zM-LiiE@8?m6u>S0Yi43-5{Go!U=PGo=oe&cC_5HVaC}%>X3h`SpKa{bvFng zo@jZPME!0zz|T&HQYFWYD;ywld(M%|VT&v8?l*~hn-s0ARD~_?ww%rv!8Y0YftjKZ zt)gFn=OM6B;YiW=+S>#`zxxq|5dT#d-V5Q=-@G4l_u3@2faYl0<)!rD?!BCgqb>4LtsI{Y;ZdEY!rrY-}-_BTlZm6rHgoX*$ zOlC52?d*`+&egZ;py_!w-E_Q2GhululS{!*Y&AuNonX`a)-G#IdUIWOzYpJD+uou< zJp})r)?s_H=8IuDzpDlfL>>hLbzM=sli5lDi_)Zv1?I*Zte|6y=R6v(k2nSnkMhG! z&c(mfPi`krGe<)bX%*2>4O$mm8-cl_T-r7!z?Er$`6pHI{={Ql4gP^r(@?^jA3+oJ zVm@(Ya}q=yWn~@;Vj%SJU_>=^EyidYa0+UzDM4x2E9irmUwkG+&9VwW<5jr*)h#&+~iSdaBjB1q9qxBFzBF(mY| zF$XpqhqLkISdfLiD(P2$?tOMuQUJ_qTXYVyI=AgCCY()8fD8NUd0{2LcE0nCQNXjY zthu?cmz*Fg+vRE~ip(YK7Cobn2~G$O&jYJR>n2YaNU4>w&I&E-7g;7W;kk)(NFQ!Z zPc(AixGt^7&zHW$dkIwXx9xZMFV|PjEYM>feKX&Ea*Xq2%PsLmh39nQtBo4Q@V^E-_%Ntbz3IemNt6;tp*=5n!KGkU-w{<9 zF!rjw0|cz3sJq=W*ysxS651@@Tjv8FKsP|2w$>mcmU0yb%Be(A9Id+NuhA!$u9g}M zPqSd~^N-og4PT05g5#MVD$2{}xQ0-mU<2 zYX2A~N7{z37d(?w;ra{rIhglf!l(TQ#xW>Cht}v?%6pOKR(l!MvWye)cguaO(nAfB zsD!*z%e0a_u@%>ZQKvq~tkc5Zp=-gR$h{A(YQPPe#G zm%)NQlh;JQBPDQSABxu9Fca^KGKpMm{~eKm6e6Bf8~n&&48`6?W~B-lLQL}Sg_uvB zLz0RMX6xO0W%8^RwT}jkOsAd=oTzLk=}nRUEQtv{YBta*OGlP^Yf>SCsUSA&g$=x3 zl$gn5_OU*^4?TvCT3Lp|uXy#zx6|GNz7?mI;H2ko^Bwq_dNAW6rp_sc<+J{uI4$9_A-fe0Uky~5+p_D3=xAqNO&PN4r6;pKFZ8ACpB|z~ zvS~M1F0uy!p*TG=^I!w%kGvt|R6iF^J=boBB zkrK}xAb$kCEIGWL-;ofhJPI4BjQq)SCqu~L-urD9LJM6Eg@^@b@f>q29 zi?S8dFhEvc^gMb+q5LHugwUs97bE*8ez4fhfV<|<$p;Efzjh7Z2r)xQ)Q51lzWl$m z5q)oF#c(a$ESO}uu171 z=qIDy*T?zccpjU)WwX|s!~f9}W}nkf-uBYTPdRt(LH_nLM-a9T}&eW)9eLEI7VsvJ@Geh&oblV9!l9I21* z7YFc)Nd>gq=&vo@Uy+kYbjA|;k(Ai?Dy`?_`7G2$mwkv%XLT+Sswq^gv>p;Z?%88B zrez<)5ZWHj8AFChV0q&qKO^2*WR3}EGxxbblB z6d~^|)lpF#M!0ZoRjLwIl?e_yx7>c{NkBo$_X?kws+xxaQ-W^1w*48 z?b=?l=w+0?pBa2EVhcg6JTX|F{o9df6{bw(XcajBNy0GF-2?bMY&=+~J;^Me_rfOK9+q&YHGb*$ zM!xet_!pmFTIyP8uxB@Av>U7W5^?Px2TJIA7EK$Md-R-aH&-G88!T^YL(GDg+1)s8 zrcsuMG^UM^nL67|Vp(Z?m{;<;0r=5kshrN7Ey?P*NG3L&1#WNppz;KJjn>cniEe+z zu-@vsDE&~eY`KVFrAMCRh{3U=jK>vG8j*W?k@iRX2)cVUW0A2H`D)Su__m*DF23xS zqUbx=cE8#IkgBlx0`A_=SPhp8b0zkwrC`E-;t2xu2;tnlsr>whdn!BVA3-=7(6B4x z0<)&JY9P&>`l$&&?oZ9~qm}o@*$0KG8)1JfeSP!by?1UPg`-_$!09RKe#FpiJ(NDX zJb9ohnR(kyIW?ZIQx|*MLEw4TtXZxxxI(`+hO8^K z--M?4f56z2GwF_CB;$8CYyczS_e+Gxvg+kJat{$hUlY^hD z{Yfnuf7dpZaGRP@67PLS)*+TTc_p4jzuWo4n^4EELCHny`#){zVJ|PR@p!Hm@Q`3^ z?9Pn0`YN~Q+Lr*q+yKJ~aL-qBdXEybhtuCL77~xRQ^^=GUCw6Ju`P)}%a@et2*!^z z@G5Lckp;SE{Zlm7;ij`0{L9*<;OKtsj_KoDDlIxl_Bm|lp+14SeiXgWV;ab&?;$?(uxc*pJ|5 z{Ilg9@CHWxoZ?#{*FbPZc;QikS}!;r2RU130Bl3SxWXQ~wOTEG_`r<6ab~al@j%&@ z`RsjhHa*#0{WP(dvSTgRr>|!sprT8OuPn{k=#7l%34^s8PVtKe3jT{G_n#leuf7%x+6NBzYCf1`U(+lN}yqkHcA!EfQGpI=V4R>?A#WDJPD+x-BTqz+ry@mcKg%cISO zsO5#gy)XJHoYqyK{U`x%b%%9($HpaWnj3q6gQtIHYp(t-McHqE8i;og_Ne<*)rVb$}(B#u$#~vUaOE`HSvsvvZjy zBo?X#Eu7a0V9V_OD`#ftF}w#$o?f7r#WnV90G0@lW+djp~=Kl1?&j0+9+9dSrWm9YxR$8qOLJC>7 z-mAn=!QJ|M2X`iz2O;)A!Jz2*_LlW)v!5AlfVE|Aix4sEXZZK)|MmI!19)2^g2(e@ z?jeof*R|`r(*ARqi@)$MA*zZMr){#IHpq+1sSH(TBO(XzW3=!Zy(jSFtj%D4vXQe= zXniuTnQ_EmC2bzlq1UKI&LBgO+J_wnTpLwC;5pF!Xo-0tsW#tB5d-(O8)}3HZaII8 zv{|KMIVGDqvPkb9dJG?MZT?}q)$TkTEh=S!m)^^Y;*$!4MH#Bm-YqoBYmcA=)#IHDJG^Z0Ohi31xeJgcK zc3`Q_G3?%@$E*?b8u&VE6^O27-f>#7lI}2TMYptj$PVl_hG5A`hpf&w9smJ|f%GZ% zn`yMx@uciY%X4%kp`Yy^7yHA%^BZ_}l0WudFs&1F(MB(QtlfTUh@bM3)O zEN!%7Uc(y&(OIfe{xB_kx)dQc+KBib^`>4tjQ$%sH?;aok-8294|?xd-}38PNaM?B zb+!m57+6u!YdblQs{6x8__Z11-+80JP8#OFwqgM8^wjTffKNg8*?Lw~>DwhKx)Fd6^sjfk z0=r>@`typk#Rq@w_VrV%{3}0*tO+Irv8cJfRCamxXq!dt!P>;hj@(45F&itV)VY%U z`GZVRvuFqC#{zNjOK-ngQ z|JuX+R1vII&hGh>d6QL^REz1o7Ak#(3-@Pi8{cQ47r)%o@l);p$`3BCo|o(U;&2i6 zUpLnR^KXEDVj$~QmyX(XBjHhMU0>7C~{1T!x(YH zMb}`2R|(Ydk~Q21wr9(GvN;f*M-w51W2L;N4E+d74v3LVmTZ01zIeIQ2!@>*MK-d7 z1)I_k5+P=5HBx!l;U!rTP(&CG_GM8jlyhR3kJpyf8OgZU`FT%mN-VPC@vDsll;B3k zeOODof4X@8S6b-@*RUS}PC6Ko!Q)^Y$r`-b%RbpxH=2#y6*^5r9Q)kxX2u3`Gi_-@ z{0DvPJkd!b^#aZllk(E$+Lh7E)Zr=E_A2G09`OYFz^)jsPG#;_7Q=}#buW%}F|H%(p zFO_m5%}Z~S3TEtN2x)@hqXhn_Z2i-l{_XWpKX@X4yI9NML;SvTO6oBPV*!a%%Aa6|Z^i!IFK%ULVN8A-v3gfqIDilhS%&E0fJpnGO!>$MoreK38|e-6Ik}~->=P@#TJ|v@Vgp5Z=arhP<(Pe_@~*d8Dhm}e zD0u6C4EqqD{+D4NLXdt8`_N3qm4YV1as^I#J4oB#a|G~a3z+7d%U8l zC5{M$h83muFROUfvb!zZp+r*wdD|rE z2=z7dyH+~;0K-g5W|@WlkPsolK!8Jb0`&3&q7c(m*In-odYKQ}`R}^49OF7+c%$LG z*pV=-uqgl6WK)PaCXIzK4fO73TH=jf(Wm5%&wwm&scpE95o zanC(q0HI22GOn|hH^$A23kky>i}HkC=0H1tqwD`=|9`bjNavKzsBf>_t>p2sMqHzE z*jDGaTwbpG@UD&hRvCoScIz6Yp8}EBYLwj)mCte=HdcIz4PzO)5Bz#-AG6?l6mcrN zn-bV<1T@zXc+H$P6T-jdOo{CyNlj6LNeY4x;t)1oq_?XcL4D<*qx~d``|SvTVro;v=@(aBpf&9%LVDe`^Ly2?p^3DH<_S zG}?@4ctx6=@(;RU5Now$!M8O;!1&BU=j$J9`%FF!KHNK&)vo&YuVQIi(&07P&Tk z;n8964d8jq=!FJ2;+vFH5p2d5EK-%5GpNLbHT0$0@}FUsCS=7KmwW`h_%;JkcO<2S z`z|i2Lu*RBZauEpyA>%U#<)%yawX^*w{3Y^LSkl#jT?6~y8Jc1cJQlYP(ph-9r{BJ z=Iew2hxck_Nj{`bo(9#poVR8OqLCS#DU+N3H6tHvZlpT`Hq|onC|0~ZY31db*WW5f zC7Z9M^)*BDXsN$X_h_zT;!_oym%BFT8*<@&jb zm7{y#`sW~fD5Brp%t^RZ4CZhobap%-{HRUq6~}@!Rs@XYm^d568-yZq6(|yvxQwuA zGVc?84}*1}EydpynD2AVccRX=<_80&<@911DdVsa3wp+?{2{P@OPT8%OGNTDG0{(0 zsW|+tTmzI@%R&sdVe}a7*Q)AzG<-4_^VM3vRTZYToMcIV0&8|K|E($vFG?XlsxsV> zZ{<4iMhjT(Zaht%|9s5^5>3)M%PgCchBSX-DSqGBSC&35lQ(vc4>?hYR#3u~rE zSi0%Cw7}tU4b>%dgt#!-)_Y0h-ni*iJa)egB}mI;gWBuXU%-RHzyxPSy_IW^uD08L&~CXSo^&4 zhn{O*T$)?zl4|Vk=E1C52>d?iDyR=Yrs%WE<6g>vS^Gk(7*=dCH# zU>$;%wxF@xt(5jB)v&iUR89LvT-)9d_Bf&3Ko5uZZRMl!fqp|0=q3f<1X;^{tCNcw zfg0&(hm0zJX3>W;{j@u@;U0T{583Sj7=FTjYO^N72|?wysRx0P_;!Ve-`l4eXJpp0-yNh#iA(ew*!AqMhmm#QN8H`kunIJL(3T zk*QT`gmaJe5gXuwJMFfVsn1^>c7pV{4!!vM7pAAnlq7K7DGQ`>S>RMivM7qML)%P; z;;q?rL!rg9wE}uyOLHcXdv+e81n=pfOIUla*G3eZJUCb`K569elvXc8jmwBr;U+2Q zq^3)-V-V=P=g0Qm38sh7DAx4U%d2<|a-{2)HnMR0F#=UNO7WYl7?0`OEh9c<6^)q; z2L6&O3dpq!sK%vXRhQPKWeFgXucq8acU6Ds^U`t<1p^p#?!+uPdhQV*hHE_y28|Ds}8NN!6byL&4VOLYCPoHe#s1PxOW84 zwSW=H?JB%2t@y?rYD#&mXIQ zqgFXim2s3v*;2~sp5ybGRXo><_e@OB3c73~9JG`7ewb88D_{|>C1;MiF9lzVc=(2L zNx0drl^%+n{7DPzadh=exiXl;2#!G@x2;1vbrJ>|v0qvMHBpr5J>%#eosn=H9w0@B zP4tR&59S)yulf~_9P@i;c>}D0-{irvmNeEU#~~^5S0*JMJX#4EEHyw7EUWSBO%hX~ z#n+8XiVj>{QUzAF{E_L*J>1B4U}d{HKo$hg?obqAV}5OC{-i^2b~0LVhq>vwS8mL| zAzuHvWc(jX?LSm2^88K{vF$FwH_>JR&*@PUFq|mSDXs`rKMAxT)~M77dl!vPr9o`o zc{y;>@zhVQ+Pf>mk`9a9>QR&1ZZPU49dV%@BnU^{NKcA;GS{4m7R}YI{kVI}A_GRm zi^DHHaPjT^zX>&9Tm^JoaBD9m+*;b(ykNGa?L!Y(8I?$1%6!9(F4MxGOUw=xKes3! zuFlcwOaqTReBmd#_7a}7v1f}i<+Zm z`G%}A5M0U;-(Z8rr~eC1Qyuv-Ye#Aa;R!(2d>rS`@SS-CJ|QZixqG z4bvQte1t_bonbPk?y719btibNQHe?tm$NC{a(Sg@45xI*1U2KMZ;eaeM;t7e5H1qNc`390rp4P)X{T)*1B&NXPO%3 z`fRQ@hx=!kGG1au95zb`CFvC2{0MU8IZ)X7)I~T?dY+mp5zV+*GLD48N-WKYv1u0QAllAXa*JYW-c9c%;%FV`_mHV}!Etw%>5c(lahy1!tT% zuzI%m#o1D8@G2$~llVR@E^pKLh9v|dg(*fzLUMo0z$3-Q5FP23jrPlWthL1t0qKt7(ge&V?fI4}Bg=8{quP$4l~k(KmREiF zYYd(lp4=JDteJ#t_N}c?GYq5^!RS^wAbRjZkKwB%@vB?8KL|5DM)(KfT&@$J#gFyY3bA9VsWW(o5B8OxXVJeJ^Vuj!ZAd*b zIn@Sqm!gqZ!T-F5!d~$XabD*>=mfSZcn2ikBZI|Wo}L(cg{7FmDlz7My6eHgT%tEX`>BR>e&#j@H>==?Ds z(z&W79h@>gf?#FN5b{sZwGPNTHzfXfewySxB<2e3@c1OY^8dK9&o`Bxx^jJQUvn(D z$cAJ*>JbOa{_J?_Y0w(+?4^4P(KoLj9k-68M=%=5K(yZTKo?bV=+yZ9FG=!-b3>}f zU64J$TMD<%zOQ4p5e;^9%pjp{VFjm*GFTZ4guE4WjY0C(9ElL+bn0r!|EX-TcO!^M zR49`_wlp|hQeVa<=z;WWw++lUmK}om@}4hzNc?+S%dZuxYEfVl4DIH9TDA`szKPcR zOx_2YT&~Ad0HA~HzEOepX`MaZS{Fad?b>}4xVmI>)lepe95eksj<Z2f2{o1Xkl)I6d?Lix7hS?UK@GJ?b0R?l^KdTbffq)RT<-EX*T#YaV%O)@y^4BQ zWC=hIG+TS$BGg4foJPcKPr??u7}oZM3^#+Bt|%)(@}+nmO`7Z?IF_X^2-aEb;|f-% zhFGD>_I8LfKgb`DVrHWgGAT(-^FPQ!uxKha9oPO8t%?> zpy>HYj{qN9ra3%WIB09O*kyNxP~|1ORVZo`A`UjtaC#_*rbqXbVL*8Yp5S3LlZ|HO z$P8VIY+Ur%@OqfWhr5ZUU{g`chEU#&H6b!;GYh}0RhfkGtg$jo3nsZ-J<$Ghj=t4x z&{%}zO%9YE=Xz8Ot8mIqdYLKh{JJhJ&$v!B-e?jpcA@{??3nc(sWYDo0_B%6vInP@ zTqG7+fIfJeGT!x-&Q!<-Pehn*8mgHkIN*1CNI~6DfOIFWn1xHd4I!6&zCiRFkqpcLNSEPCL=vd+;7!Jh9PSkKOYz;5(@zU-jGl>5(<-g?Nv?6VEvVRt=vBh^-5D) zEsZjpXy^!uR82vuLQS&QtrmIjstuZReZqp*`$QcqpT59%>FLaz-Z*_^uZ9zJogTwm zP=9R_vVA{7kHsuiu(>c$Fw@r9TVw%b3D&PLt}@C$6=xnU%Nb|7>wWp5*cBbIs3H33 zRRKjb64kPl1||E~74C0A-Iq4YS|#QtNTQtHTsoQ?vumY>;z&I^0x}UhQcY@;!5DljzHlSWriMrpx1z8XulK5Ux1soXk6FSWXHrF&dQy_M;OxGmNtDCP0k##`yP9;7~I zCla%jenGeMp05X5vzVoT?>PMEv|31fc&8R%Xs87Y4UfJk5M_Ow%Z6j;ee`V`*?^T?S!?H< z2w!u)Wd&qEBiESXdcJ167iYTy!Fj(ET|2GcR?&~YDoLl$G3KY) z?(bfxI5@g!vU?ebiajX5pu2sacmr5TK~W}Jq___Gqo1b#agW+e&R%>{Su}L#^+ox| z9|A+BNi(`;>ekK0-fl0M?w61amya{O9vzJ#2+?`A=_}1zhy#r_{}MhjLij}Lwy1)* zyl7xmlpvkJZXm|YunqwMQT6wZE;I_ot5KW0W z5ioP)29EYD|LoC466!Ja4b99X!3{MtS{a zj(}=4q1V^1(Sy>%Skh;hgTd}fDNRdE&N}Hy5xUXoFB4k$p_;G84$mpkI9TLCF?khF zuyt~a6m-eRlR1b!H>ca_zK^ex3N?-u9`23&cs?FN;mA_l7xv0Y5EPG+mNB+=T+828 z-LFh5=xCnwu)XIP3}a`3b+#>qeoMiHfnN~4u8TrHdUy!C%BL9dUEV(5Jc>tvG?r{4 zbAtzMPT*CmL{+mfNN{4Sgt8kZO&A4^{+^}Z2`hfh&Ua;E4OvJVN*4EScjMDxs}4ct zoK|Q!NK)(`BU_dAg0^w+VyvgXeXwg(V%FZLKMOa>C;Qq{Gnaf4jIEt~!+e50Qwwto z!#!tkNPSaNE}_0kS^&FEMh9KRdlfdy{>Uk9N8RwWD>pSa(0$y-w`QWJVI65NlSS$2 zrcW?G6^MLhTtVGm% zbvSq3X5#l2@2@7I6qSs3tRo5Q`|tE$pK`zr!wwaAaLI|9%5{M}@Pwn|Ub#OvztWJL zm!fd=qS1K7ZPmtww@srp58;W>z`lq#y?xrFXkc0_9^Pd#M3EX`pq}3TFiq9=Z0gAk zackt31~(Hy$y!Tmlg5>G;>D3;UM@)2H%ku9BhQxcifPVUev`HVgqiX5oXaj2s`Ag2 z8MF)IhyF0V7H7SUHBGW{c2tnqp)_N#4t)*M)fm4dSx6V;%eAs+u{xxsf%Ar>sZZ$o zi_k^2A?Ek(Bb1)9o760kE_nk3Wd(%_??Vt+ne&4Y{3j|xJbmOSS@Exk0!?@68Hxt zEAG*(k>Y3hZP4)rVnRxEB8YHl4q^c*#U3(YDap1XQC2p<;X$qk=4fxqg6|oe#w`kz47TV5G`mHuAmM~z#K${V%TbPYHS^{MQI;0zkuQsLnOY&Obw_n9vC_;tMa9LUaQS*>|R zr6`+A(&1@yGb0Z1cD+PZ|`Ij*DCtCXvna@Dy-5SPwp0w9%3 zkHOYrN|%H{gsU?N8I-E|D_|=@fo*NlAe%b@G7HpiWnRKYJ|Y~>3l<4p{Ro-O8C91+pGkPyMR!AJP#=!9s7wR(3P9jwKDBAj$BRnFY< zmp(i&(Hn$55Y6YL8xrp_G8zOACK>bPOP`3vy!4AEcDp}WEu-Q8=IqEEZ?nkK^;)K; zRT%V;v(CI|W;WTDrkb8ZX|PM0+EV+Z%R)-qEY!O)OaL9bGXm&zS3D^!jmHWySKsSC zVHwIh>9*5a$<{Q&6T@VumEPZQPMbTzlDq4-HrgBzS6`afw~X=joiH~OB~!gi9v6n_OvL{(tLt~3fo;w zhzL*<7iEMehN6AXBB9R4Yuum*$gz)viej?v8ZVIyH-Au_i>k6h8Xvi}Y*ZP7iq!NeQZUje>w}enxAUNz?V}!-J3IAmYt40I3`RTo4_ur3% zJxfHdpJl*DDzlIo+`S8P|E|Jh*6PTa{*HbGlPyHlsukVoemVx_*wEg5rTPjDjbWDl z&^h#Z-ecrZI`(nFKKj!6rPzIAV^JLwI`~Vok?3OPWQ?wrJ$*4zy#mi%;x^Xhh?GWI zi`KDWrE_!AE!oN{UdD99myS7D9}n9ebZVUdaG&`D>r>;3(^r`j?OAIpKtKd*OQHL> z`WcmsI3Rm~!631dw%9vkJYVt|{D7pq?>binS`@BFVp8}RnncV}yp?Lvoc3DYf|E;B zZ>uNW*>37vhj&SHx9OD8;i599-h}yKWM(+XIn7DRE>x@kmlQ^hoZ|1f;@`PR4aI|hK}A$Z^$lXMuC^(DFN$P z04-0RA}G9<6po2tWGT4mzkRP?8b#R&K11Et?F<98LQu`@QqMIrGj^0B{L8vDx;NqR z&@`Ifod$anIc^z5&;3!!QDZCT z;d24I^pk*HV)2-wFpn~*buaIoO8a68*ymMa7032nl}{E%8$kF!8suq&)3bm_9&#{% zMc2Mo1&f}FVh=(lRk`N<-~l;4L2-&_cP0B3lj|97MEr0_IprE3LR}gg()f8AA1x5y z+zNP09Eah3Ge#_k7^AF8u`XbBch@-d*uUheD!h18Gb%sPo5ehqt6G>AAXK{>HfZ>S zyoA$m?M}uC^4F%kRZ>Pz2l=qQ9re7`jN@nXaDB2?q`kPayuxDPGacVQ!co5N-cugZ z_Z^w|{(kIR{~(8QB^m2}8bVOO5TdoaZyk31!{;GHkLJfUw12+(sr7~<*F-_wN+3pu z+g*A3V{3a!yTRm_)FdgT%kqar?3xF^$&6eI?%ao>T|J`R3Dn#BprSGYyx zMOIgYM&1oPo1kswHqu?%TRL0so!fceZnn$jQj~78<11yPE=P{Js`0WmqDNpG4c&Lx zc22nFGYrgDn{10$-c+|U^>VP!xFc_4K4f0`Yl)^N?nM*AAxUc`S`)2G`>TY|Y% zRz8#uc)R?7;mA&P_ph7m!aA3v4;pe~mbazqv(R=r#5ZbONf6bgt@Bqv`puCK^+mxQ8@UsN%eK(OBJe+XV7{{UXp0xNE%%PlFFy9U2d( zrzG{Cm})Jl6hubC;Z#mRFbz&(v^pA%eJZnJzqrJ7#r}DndN+z7863R+TOC{#)!gw; zyXG_Wi^!TM+M7!E&%S8XKj8UYMzk!Jc_pc_C63WBuk?c&;vN)q?NWJY6TH?p7Bm|n zvX!epfd{7j{hkS03s@sae0!!ua3r?% zXxbU^Z$+2Sg%{n>vA9jLo(!z@cRo31a3hMTmDf8#_roJf6HqC?Ec_q%Dt3%b!IW&Y zdgE+@@0;I1#dUlNF!C1HftH45LC=hSdee|pKwdVHh9X}}xz8JGZ1OEeiT^x1Ukezu zC+Ft8m^zD5sRpM|Zjm4Q)wxC)5(kG`D!GWkX_@|EN|3Qr!T1S__~v3UF;1G*9(h!F zitZ^J9+m;Ct=uOW&@!yI~VKg)BOsJng7@Ry$wcu zHv|~~rV(Yndi7V1MSg1Lm(Rhl{0gdLbJC1Rg|dKqj%1FcNMSendU-oG!}-j|@sKOc z(2ep8*pv{1g?vLWZ-+vfucEXRMHJvSF%ioZ(gj*g2i}DewNyK_f1g8!l1f@J`JN-@=*+5vFX!bIS{^-NXP*(`@CFqvRv4&~-+jzw6U zOFYMHod7+9@6FDQN#CYVZ`}TWn0pJTJh~-am;{1bAh>&QcMlpgxVyW1aCawY2=4B@ zxVvj`3GTsy<-U-d^CdIiUH^Y3XYR~muU>RFy}RkIy?519PgSi}M@WOmvJ3msFgfYN z)4yPJ%Zjfb(96ruNg}x(QNaoJdaI$K1WoXI&HhOLhv)1VrG|ieqzG`gBTgbY}E^pKp4tgdZ6E@Ad zplkv9a<9184wVWhN@a6Pfq$d)^9<%x9}1HKz?4PiTj?3)uv7G7AKCWHloqNndz&|= zWz5S$EN@`_?}OXr(KABs#3YQC9TrP$D9oop_S|PG z3^OFDdVU!kuSV60v)sRrL^cspa&>pdTMy^qK3HFcK(YFq)$*^bc@po zDIm}~bz}g!P|1w1-KpX?PMjdm-jvYAMTBAT34T_o^P>L*%1xce?3AnrPB!O!*yZnE z>Ky!0Jt*5Nniccy07Z#00y{FdWotSirW2H=iD`sss^ROk%pFBxSmwgd%Df?lZ_sQ+ zyFbY~mFb7-D-kZ$#oqDSuTc%d*)*$7<$`ha;1Po3&aM5OHXQX$Ymy6|mzT}SjxPa= zDp0VzEz+Us0}bri%CB#Ep~|4-LrP2dq`Y5`FNhm0{>vgP(ah-Q_!(OkSqHbzk{$7i z=+WbIi@i__&0-?&9v{$KVnBXqux^ zvUMj_RDuEVth;E3oO;KQ?N9(Jo-QW~1xa6JT5YoXvO{BK3!aXP1%ZKkoxzpM@EncF z@djlpf+S$(#NuE9|ME7)Qm&KJ9i@3s!)iZe8FcQ86Qo~oOtH0Ka7#q1D?9YDv3ecc z;=0J;S|bfc|KaG+Wj30s3(^(@VV&j4tMQ(i5k2^7aXpuhSbw_?v{veF$WKtvo0`yC zb|T;WVRMQwRJv`V=Pmx@mVX^}lq|N+N7Er^BQ0(BR(c*t8aWF8M(gxZTtYUKojeek zVJnLNlO0R!X?C0ags|AdR|$?DIsrjt&K))&l&K0Dk}}+5nmq>XIHQy>ftopQZZET` zsfR;^f4-unF}Ya5!yHp}V!~nKLf;gv;+T4aw~d_ zUnuu{1PcA#aTfd`Uz_Q_rUmG{RG8R~_7(N;q0@IrOhLh-U@G>jcD|45W7rKW0F_<^dB4VhCkP5ZyK5*EdOlV%1 zFy@m6q6b0w=-OCA02Yb>w*a>mIN24y-pug}96?0JnpHwVoNEa8te0#0>w#lNPuak3Rnx&x+| z5b^+vTL|mmkCD2!LqP8sL-T);ja-eW74LnvzSK|?}6)HvzrA4NX4AoQge6=jg{I}1;_dW~N&gjgZ zy1XV8F^cQygHa=2Ar+w5b72#vw&gTHp3^hV+4Fq)wLG{*)$%LbQhfJ1+tQ^V25FF= z@t(Qj1dyT}EwY(R(A6f+?Ep5jKzmhBtGEWq-PYu;n1)7q+<*7+H`*tl93{+z6t z^Um3zs@NCe#3svTGUgN!#gDJG^f0KG-x`qf_=N9&Oq;zT-v?^ht$PHp}84z+J4Wfa>lN)|uupSAt)b28!DA=BZ zm^)|Q_!xsBa>igpRF?h@eK1m1qKQ|!rY{l|Sj~RUov(O+6a};5&+AJ&g*vg_(l%Uo z75_V0a8l0Kg=2C24Ks*eF}T2ihqR3r>9F9watOkEJEIGfUKbj5j4v%CKw_A^Rli%) znbuef^JiC6@MpRpmY3f_8l=^M@U`C$It!DO#fa8lbmB*|;KnK98xI2+VHjy zY^e)^j=8N_!-rCm%r%W=${a^U8Sj3F=!=I^JFI%bcf0WpbR|cp&udi%ND;>=iM}$z z^uKPOj9?zX>V+ zUeLO35{22b`<~G~%7`=ddd5Nb)F=J)J4jUDM`mfqyd5#4)?Z#D z)_>sm0@ZA-2{UX4oR!mPc2tl}Ei32RQFiA(H|XWjwPoA98^L69jboBoFVi~<1Pu+t z%E(6HVFxEY2a6iG^QqW~1+<>1;UZRBMz?t6Dr}L7{()QLq@LLxHEN`9S@d^2w5G$P zXBVxVT20GG@Fj=kBsgD|mXB^{XIV6QTQ-0~&|?Dc!C{SJZNW zFVy`Z#Vbu%Brz!o$6q>{rvHDv!}XiKQL`VyeQV{Tw;69{T!lK}RzHM$ zz|$p%H;;rAys_$fX+wVrA-IAYSi__N6}bq5+k2i6(w)h6KtGj?9Ug|O+6J0r*|9MW zd6`ff5qb3~W3!5LOWBgFX?e3VwDZ=xaZdI?o^z<0nb1f3)v^ zMO(nk6-D#0j4xT=x%d1hBn_AW>lo+ky}p!?7dzU13U7WXW3<3Y6&9S(g&N+Yig!>K zdj0Y{i1!mjK&@7#XE+RCIk*MVb1di97pi_?M`j9q@sv7UA?p#`R0fUqXsEgg+4xIU zJkT=USI6k7e>$=@NPU8IG$~4uv za-(E;$mLJXT`#>73yvU7En`&zi9qF*=;XFW+bX*vhh$W;v&gR7iyj z(72)qGn`ka9AFPCaoa(!b!fnXOmJ)j)XSg~%OF(`p2aUIqv$#t)|NdNw@_>QG6?#C z3SPam_^`rJeqisbgZE$p1dTFw19W*)m1fau=AhFYc7wL<7w^IN?ocHs5~`6%H1wZG zqN+eAxo`4eD4X;D(NQ_OZQGYVXLbLIaqi$4Hjbw&fjvstJ4hbtze0(y0QUWKFczc& z*{sn06_Jg@KQ2zpFI-4Y&o^C6e(DDJXrwP?S!VU`CG%^LJ?J9v*0f zJ~HRW@uN=NnVFe~aabSae;=p6H<7B@3WV%U#o~Z&X@(pFXOFTxT!zfpIP2nxGYS^| z+y&sI#I&7J)V3i-Jn$I9(2LAp94I(;i$H(F!(V~bPfL|S63ziqStDtgotZ9AOi^TM z)~>!^!`DV)YFxzJ+=7PU+{fAPUg+>}x_e=&7QC;BEKf=Nm?$l5Qux@sPBDpJP^7tN zKQuWdFW(DlSAicP>}oE;?(s9x$y*pOzalsUf_cEK6~9nV5aRDSd*7!!Q3mS}_VJ1I zfpeDpCDCF>5?t*Dd!9%c%9ncdO7AKPNWO51U_-G6E+i0djeQ{3_*BXJF=js=%9&H`&se3N#i-IPj#10A ztYR(bO-Y|C(>!494u^ASqCKLau>6>DLYAWd*2<`*tJ25JXa&hDQxiA#E^q~?H{Uh= z;x4E8PjmiX|H19Ht;{7Bt=x4ubnn-fA&miW!PJ!<+7=WcKK`}aQ>UOIicNk(nV+0i z+e$#-hGih_jMK0Yxt-owpwnT^RCf9d6_<`{cP@JJOIn5m_aN&O66ghh_Ttdg*&|iX z?ZZL=g2(ywn7W`goD}OmuRU|mq~@uMrq6_nRBH*Hp~7MgC<<;W@VQ7ZeC{k?V_#Fp zGj%nT{$=%_aZ}?2wyoJSZ2Fw7KXm<;4U9qYZ)ywaG1aWo-~2(pO^UAZqLER6yTWjG zmQT;Yv7+-BEz~`*fTULUWodqpB{dXlX@6XsSfLO7KYxp&k{rlpMw_A8RVgH<~2n@X{Lzb<(`V=SrZS8C(1wFLJfyu2kCYaNcprV5>951-Sw_tay)jBqlj1i3%?prIoa*F#~_aw$pfW_2FAmp<4{rU~9l(VKA%pZ-3yNVE) zoa4hU{3!olt%chZauV$Vg`+}g-sc`*9Hup@yp-qz-b0nurmKTE{nXF+!fT4#8Ju5G z#gK_AH4zEDexf1|6X`Tj{gmwOaF*ggZ!9@1FZVzUDj7GAs7b6i~PZ?NLhU1p`zIN)}~M_ z-p~#~NL0CT5=SF*b*<5MUR8}HJ^O^6gFV?tl}#8!74gjWiWRBeip)-Zsuw4C2^8%1 zLtUK{tCj2+P&_{_E*>`}I6jJJmBwcSFho2dkgOM1g5@%x)FR%Qn&83Cm?XLh2}iTv z{>o-@E~;L(yUe+H{R2|))IzOn!f+c-pHliuyK&#>OB@I9Em;xTM}lc|bZ1JR^3wLzFfnbX(P7h@^e>pSD+%VI@1 z1lVz!n(Fxd=p}u2>_dkP3|w`H)tsL4jI$y%2AuSBX6Dtvm{JWjDnzCD&hFt^L8aIv z11zvwSIb4q?;vD=cTN6pS-WT-9u13MtV>T%X&VLm3xsFf6#3-$$+yTO1O+M1{CjD| zJ-XREGZ$!zwCg4G?fHd#S;6XBU&w57`R9e!?>dqVNZ&h{rinuL9u9*l>X|RR)+xKR zqNO=9=N88|52C-73HSr6@N;V?GQ zg@`dLZO`rR5QlM!*rbI8J0)+eNW$q7>}=2O+@3Butkh`B?Mtm$D%>63tq57X$6@H@ z)IYZQT^Zk577P$&;X1mZS1x})hgnMYJOFD(B@XHfFwynQ;*C>&V}&P*Nd%nWF!e!f zSc~Wv{hO_G$x;uWZ|P2&g5?V?Zh&_5O@5WCsUy+0PMtlEm!DL8=@N_T^;Z)XsE8pa z@>6!OEImhmU&;-i35Bn72TvZ;9?2RDOZ!& zryLlX#VPQGqSeTx(Aou0hbX5N7NPJ{hLMR`v!#KNQN5Lcp^2ptG#qZ>nv08*gU+5Z zsGh>)7q{@MxKZ%Ol|BVEiO)CiJII*VZ!1==d<+iX-p{f31n0el5%D80D6}*q2Rzyp z@@Ir}k5goOVU3^R*t9fTEWKvske4(tcX)E;{?vhR$Kz{8{G<{{3w+JSJIM=FguvIV zma;(OIo9^uy&iF}^}A`Ei-ewInmRS6yYuQlYuR*Yd@w1AaCF9FSaN#wG z^>>gPs{f?WxG(?I;Aj4c#qd_RAfOS*VY{|rXj9-qRt~@UygY075dMp93Sw>w9diB0A=&DLE>9cjCQ*f9o*&)wFYq6tIA|=r_;EYn z76tW0Cw@9;Sw{PL@s#zO9}SYnh$pA0ph84Ef7Sm-6K|r^&=6ydo#Qigz(%ZjYTldR zdix=v`%JS)i`hJ`6UX7&^r?E*PXTA^}TPHKWF| z#?p$$KRQ;@A^5-=+~?xG_4TO_;FT7JMuxz=1ECA(|G1Tx7XV<==kC9?{M3s!pWo+! zp+Upx6qbW|aOeuN%R>^NwZ&fVCbL>g!O3W`%wAG&h&*a$s;uoEzpgevCibNmr%9n$ zZoJ88rMD*{ZI_T~GyW{=EtmrXcXQGl~H=uX_dlQX8KXL2s+J2pafb;>9Ws&b7EIR1N z7ODTOarQ;4)?!8BoUqjY4UK3{CrCmHqo#Js;z9ctSPqTKGv<-Dl7e@A+n=6W-Ye-j z^z1j0I|+ojwVxu4fR9izvjnF2PQN|-4$?|{dsYQ3W6^QH-P#Gvys35d1-O+^4!n+U za=H7l2i)piw|ZZV^7=m9wH^;X+$C0^eMQ;gcrd#E=DG6W{+kuXooAox*H(mIdWifs zaEtvNg!AVmrMyXZA67UXq<>yQzb?I97-j=x8vo-l@*b=L-+xX2r4Q#1U4^Mu>lO=~ zfO3j$#ch!eMPhpt7+}FQ=F>*b5iK4;RsXNYQ+xMPWm9|DUn2>kD$1fB@|5-*Jo4n- z({Me4YhG-B2Pv4oNz*ErqThD*;OlYryx?e+E4twDVk|?4P(Oicx|jS zTE2Tp2P~ZU3YShS?b2R<`YQlURK4N>@${4c4|xf(Wg?tO{0#KvNPEAtdeUrD=^egS#~Qc& z9?9;go#j#}0BQVPXPi4yTo_C5CG}iW#qTC6m8T!qdr^_DD+T*Hl&M_M_~-iX5FIO~D5z=PL8K7L9HO(T}Ljrf)T6|)9H6T7dY z;tNR{Fsq)`kyU9SO*6=^#zpV7KyR1ddua@TDEtUue6lBk!%^_ti5J=$-Tddtkk@;z z?*)w)2$Gh-xkc^pkrfJ#Wneir4i%pZoJk!zBFXgZCc})`oU%>e?qV>kC z6%y^FUYeUD*wvv2VOv`BSQ`HLO*aV@f0(^p5%}i~4E`|gAyruv3e&14w$cH+yboBx z=IRx-$y=qK78W+Nap+xXe%Yt%`}kj#&;3{GZE(ebVyPJ6yrjPy=DH zf~Gh8D3qwtlWpkKlbj@b<@~HjQIuq?Vy#f6%@t^G%(B_#WfXGh7*QOTs8u-`%!q;; z3Ic}w$`>cC*v@sg-S|nO;+T&P#vPM0qfq^&C4t%b@}bew@MMzaid|sguZc-DIaLpS#Kxo9uoVF>jR^XaI3L8K6C0Q^^Ytz(X4nW}E-}09V zcIAPGPk@443{P%-wK_QLf=wxBS7ht-_zi;5yCc|Gf5Sr-meGeOg71jZ8VD*C{mxvC zAesefIUNIGSYf#9kgh2MU$nbNhB#pfde-Y*Gjp^RI63iRcT_5s84}#s6pWBAk^nOZ zN&XDVF0C&8>~|1J%h7LHP=Kb!tTnE4;Ic9cluT~7st=eMI)cWGV6a9LN;Zk)m2a2EI_JxW#I#Z#<|~O1YO)&paHek0l`P5(VhFGb#m+A0c`oIK6ZS z^{vHu$9;z0Lz7NtH`dxy*mL>fH-Y-7$)6Ahm~p{En?|;ycZR}7tR#f2oTGI?+Y3w@ z2uapoFT@i9Jf@+(B=j#IBq?L9N|PeP==G~hN ze0|yua3CXX-og&e{bu~yTFttz6Wxx`-HYH%gvF86rl&pv5y>Nr@{Ql3u<*bh_#?{FqYEw=Rqc^itUD!#D_W?=4Hj1L|Iek<-|h5>qa=>eXP_OzLE%1 z?*t_dw$5MC@Cyo)@~AoNr?O9uy_jv8pK8*G<`~s^MR8_J_rC6n+^KBF(%wVvX(3AF z05Mh6_kPzKgm(;lneD5W%(-ozN|DbU49`9!+gj=j z=Q7=uElmTlf%tfet=_ZJ5Mg@e8TsM@6BprUo>0Q?ID=oG5J>HY&;BEqikQL0eM4)}a|bOw*L-yLW6H<;Byck; zDI-(x65(w2*-mq;w1AK_CJRVC;zEwrU{0?CAb@tm8*`i*q0=oD%79YU& zeO_;q!YK40RiTHjnjC&Jza>_XAM1_Yl$KY7Q(PSe515c3yvnkO4MmYl!fxSUQ4rvT zVOt7*+wolCo~LhyRSSC7CtgSv2%0DLK4IHQ`{3B|rfe%Nr$Dt=m@ z>J^G)PKOnf%t0+Z!SqcYy#4tzhvSOomd1L3LmWsla_K27D-8V>p?^Z5=mjg zGLO0643!ZI7*Jy;+$)c%Ou&H>U`6?}lB{EpD#Gi_(+L6j) zITgM;T%dK4O+Hu^1HUY!O|>Ag<6W=TJ@bkm%(XgMX_{a&`v%00PuB_Ae4P^`MLx9 zNO$NUc^U@Is&Y^dd+_rj58%T}YElNlAR>^Zh$3E92&Oz^n4SQ$Vjb+!J0u1Sy2xqQ zo}I8MM=zRD`mj{W4wrm@lb&urL-saCFaHL%1pW+Smfgb9K69zQ>(%MK_ctG}6c;f? z7DJpZR&x{6`pgR{?A=FWqxO&iF*pV4ZDs%#wx%j3700j_Tu7a>SR-JRA$=fz3RU&W zdHT8USZ)SEfV9oZEzGvUl+c%=A-ppqJ^KYA6A8UPc>DLdLRTf?t01MS(+I0-BkhfGz;$PX(WZZV?;T%OitM4osJDc#F-m@nY; zWZDG;e(SdjO#nbk`96jZ7n#N~gej_uxGxMnsf_(>lQ_)ud%6E7E}M|bqh~=h zscf(g-$5oduK8O1J6v|B#3xH1=eL~em_5bJ__YBQmbm)o?E*DZxa}{B0Kzls2o`AOS(QMM*xWFFoQEzF^ zi|ELZ&}Pq_{^!q>Xn*y4FJUw)B096Qw?+YVmv|3R zo1ZaL)C&5fvJyTCyK*$zg)E>_TglSbSq^{s@(|zUP8GGJnU<4qn@54Oh4p5|WN$cP zj~G1-3zV@>t*@7uX1x7}>Z{8iH!EBAb$=(oc$a*K9H#3M{rEL6!o0SNPpM@sYM?w? z`Yg=KT;bA#HULo3`0*6gd z$EE#Xe}p9hkyHp!=}hAe4$VEulj4>q1T8sQG~F>yrAgC;1X|XXhaz{%Vh$*3q~z$2 zhV>f-ll*J?UGs%1%TdFR?65hA*=AOmW;x!36s(wQ^jCyfx_VdsOdWdX`lE2v$HQu@ zdVVbC4uM2YwP{fY7EU^6Fd;!{*m_=0GW2U(-iq%@dCT+5iM7|mYFVJz%lk+P&?=r+ zvSEn9Kt&!(aDv_jPHS zLH&IW`|+!#DodtRF-4jF?1Cbv3RU@OT)!&da;7rBAAYm&Gf(>?NH35s=Z3S&;R3}R z!x;!7=)3Av3CDeZu)2%M7{Uv5W8Y06iFU7NduWGi9^y#o+GxqY#_xZ_E8 zr@Q?GVKb^(E>gohvMA+|fQoYDpk2LcM}>T}_&;n`&Prwg7FK`9rm8>eDIYD4Pw|)t z<>tjE>vph6Sofr}TpsS_63~m}5ZSRDTYBshFK*6H9Ddk?oLFhTOzL}`oHKVnEju$l ztKkX+>zs6tObK7N!X{XXLUNOQHP3_|;<0!=tJov_E$rnEH%0ri&Z8FB_BPmUEVUSk zvvcBF)ibR2d5h(fvN?NVJcGG?j%Rg+!KdFQuCATDDCEmw2IKeTF~Js7AQDv^-J)C7 z+TQ@2emNpf zj8+{?N|#Z>M`#U|QOwiCK}MG_4}1}#pPN!(xjZP}-I+WOQKEJz2p+G;g?1oL3LE`qjzv8 zHos8Zdcz9aTscuWksKzAZG|*8&DS;CY$a6m08J1CDzVzz8(7J`kP{HlSL{(xdEh=E zrCVhvVcmuSqJ#n?(=K(v%n;nHyrIuaqlCl}CLAk4g$W18G8tJ@3G=R5yc^p>wMuue zI0Swu&B-4vSEb^0EENLltK8uw)dLIDU@uGsZfa(nSskp4x?d*IK%U(DZc6tT5OqLb z;~?v+^Ya|G4i=j?_&l{uI+M^Tz;&T?_S#?Ac46R6TLjj^+@i-VLobWyz0^2 zZ6cqHSk6rTSh_p&8pKg5rLlUM3W^1WYC0ZVPVpp*nIi6zhb+e^GN*oPQ;~_Nl{QJ| z40Jmfn&}fOZ0FaC7l+rBH3wt4Z6Yp&+y%LH?-x*g0ANBNtfLhY1KvfJq*u$)4M&cY zmB`^h(MX~whD7@SnglFQb*PsDtdX52Q=^OR5$GexOkgo{nvXWweKPv}RA%%dKTk%S zqA4D(zuhcQ@gEJcVCH)^Ws;B1{h{{vsY}R>C}($j5g~RA$<2ZFlHBC;68X~ZZJuMJ zNNwGgX~lNTil50|_ zP7xW;Y2VI(z!fWI$W`1b2e_h0-gYSiYNr`QjzawV8%B;79jMXurK-lbp_|iSG|RYZ zJt^eXny06iYu;$X1veyRWcJ$q`k@AZWpJMI7nnRDVBro9Ll4^kRMbi8x zs0)3NNe1OlaR1_ zmH0oE0plt4M)k?!@+{}+XP*Gdp8LlCfUx~QZg*RO&{HQcR3jw<-m;{4Dvo)|(moZa zRv+l;c0ha`eB?9(3LfyA%gE_4piSXpyhm%Bq{ca6vdhgk2ihHl?4&$BoAh}l9q-=b z(sU7#`lPKa4~?e{rt1M68=qjxe#*@;oXFk)IOvvmi1D7!>TV;(i=aX%pE8UhT`xqC z(D~P5oaUSchUdp_hpaj2D-eR|n__7m*m_M&U*nJ-`N&>3Ps zb}b!)%K_GhT5lK`1&vvmaJ;Ix=o1PKV?-OJ*;)H5D(P_j;=3O)!X}^0qrZbJ|D7dq zpmUUOh2p6t3G=EZ;=oIYws27b*F^8Kqb=0%qGHei;CSVz^N_vw9pvGfJLXhF>g1Y7 zurzKJ6Iz@&E$lbRXpRG$E4m8$aHE8MbPUe}qR!&e;mxUouD`wxM&NE;vkS~O1L5Mi ztLIUB`J-6cWBA;-E6?ov{T{$co%J1WDH+h%!2w1|ZLNQ)`fOikxm*6GFt?=Yhj6+f z&x#P3Ia3uG4hq_WWquX1bwk0ZpIz$70JnW5r$vbKK{z+uk8Zz#D{6wDB%qH*X$p~( z06A#p%pD2m%V}Xq$Qv0xU)i06#V8em(7sIgH)OIflZO3ZIv0Ht^p+ka!B=+focc&s zIr&ve;x@$oy=rZoG4CX8DTM|Py3Bh-2r53qmT40<#AU0x*}m6wGTf88{5x+WCmK3N zVR4u)Q#M{!6=1F|kRd!kGDV1xU_4Mb2vR2FUEBIOtV1+_TL*^p_*}pu`_%23opP~k zAHy{v^aPsc+z1dvg4T7*Nn!h;3NF_N!2=MRnCe=Y&6gq&=gV1W!9f~|ms(zx7U^jl zU|9TLgs92QtkGse<65oW1Fyx{mL9L#Vj15ym`4*7-y4ingXB|sbV zXGfUm5)36bodgr^Vc=9F*ZCWuI7ZhqTS3TOd?oDG@0-Mshw&-1uj z{JE3mD}s)aHBb@)Nug zaSB`mdb=n%mTmr0X5#{q+ zR+{k5gbw5Tri{2IR1qD33rI?MD#d33RvRNL(;y0e2s6mfa2ouCply})V-)jhDcN(v zN4wJ8!X<(+Umf>vDQjVlDcUOrDwYpVAKn@@dxn46Tj})9aTB07&m(GVdSh##1H$P` zpaSRZDnQEm%*fUh=i!l7|8fm$;I@2tG3pC=7|Fq7*J6N zZwQ7auEDft2({%XUx<{tkq1@{Q3)4fdFY^g0PBNVl=kbx&7Q4bfNmIhSl=pKwfE2r zpn@J37bJ-*ABS1gmUCc!O9b9dVoq|nF`;+f^=gzxh!qi1dOvNSpBN!BK3W-* zRgohCD%ATbaD+h_#Tq@NDR|KBhFX)(wQ zu4t%RsMGB}3~^O8703R?0sB+$fBlLbBKSG?%*&utpc{7or#t2++OWp_LN4?OR2fdg z*OTUyC(>nl3%H}r)YZRPOFjR^1GBwN{%ha(A@+bgrX!Gr_|Afs*a<+)SJF z_2=|Nu4D7iI*@m)5YCr(;EBrbV*?)ll-cW=m+sr=HnV5NzaE?!PCu>q7CLhIcs-~D z(ZgF4Rj>z2DT0URLBdN#5+8@GW|n`HjctawtJ^8lw{Pb9IZMwXUjTXVU1Ezuhf`W} zx%K9DxsLT41n;IBUO*&^@`ug0lToe4CRo26WF!8Piex(i#cl+aTID09@-LiF90{}t z{e$a&yfcoE<+p(R|617?UKS%Zsz)E)523)5`sRFS zJ7z}8n=0FL7F<9yYA6zS znm0Ya>H)QsFF%M_`*||7QqI$$5K8iYSYAc8UOVd@>^t<=d!T<`rjbcdOP^L=rQvF#YbZZD}3E2s8tp{{{J^RB38G}GET0b?lB&#l?Bv-HQM*o+E zk9W3`FDgXVEkUh^l z&OnY~7tWXa?K4Z|kMH-keN&3em`UIqu+qpJnn2QnGnVeeJ7t`-HQYAn?U!He_SSzL zz7uQEa;Hl> zf4>$VBn2|E&H%vi$!cd~3-t7=)!EMxD99@=RH^!@MSLj?aYIY}Da&L!mAyC6MDqy`mDl!{ zoKY(46VGn~2HiRtgLz>3^pIke5AviLw7T;g*IYCbM2MrTEZ^#%I)=<&_`R#AYagqs zeE7oFG`XTs6Fx3K#(ewxP|sWdSS&dKE&o71h;Wm${}CSV@6=&R0ZAV_Euc~UE4ug( z65M~}*>Z=34%f+_fc1POml=(v9MUrAUn@xPjtg^+SEnQB6v8Nrc!p|xoT?^orTXpZFBAiVzub9^+2Lt z2B@R5Sg0HsnhTZV-ywftm0MdIUK?MqmT?n0as7^o-f^D5i(An;!_m~P?m$y4+JE@V zvoV1Z5^kYxjb1defCRJZHKN{d=CEFVVh4}jEAnIE-_(Uiq_6ajdXX1l|L?8mn>C=V zYIOum$7|a)yjjOZn!640?sZQ@sTWKb-pI#ptF`X$Am>|9ybqt*sTOqXxe+UOfK*p# zSkf!UZKsM-xP%S5ghb}yxu^~m1SHPvggPq(?2^pr!6T3kDg}klemT1PNZ;3FgIv96$;|FqThzv@mqg19 zO#|b@)RIHzpzh^bPL9@f+schBS)`U=mqtK_6KvnH6@wMV4`*}lN2_&(fm?uW&r%At z`LZ!Kc>*1UDSEho&+z64?^zXSTP$RrxRpe$d})2}dARZ$MQ;1_eSNfigRcB)q?oV= zK2&C$7!o36@L+gV23L&OEetSS2IeY4P^l>Z0PsjGMc%xo~%j3C0E2FqNhG7!rk-t3P z|K!SNPr;Z16rfOghTrz2y(Wb)n9BP;kJ^q9C{u@wt2TY&;cMkk!AeE`& z(Qli~W|**!WfxFjMhJ@DKD=4Ej_#Pv5Yz>OZETWzxO{+S?&gRHhod_B zi5EgBa;r}rq7_l>CuBL+{*v0)5&FZ@xH75$C`~ez;0w@cr;~V+IjC1g(we97 zTKB3ubv>QEFC!Sk`*nMhtAv9r+JjD5aPm=<=ql2Phy*mSu(YavgDbCaU0Q#vT`;c8 zF~c}`j``#{OQ~s%DDGia>6oHoIXqPf97lHt4{ueqv;b5^mFI7y-;Jrt+p5~ z%|^3o?j)QPhwJ-Gq_lQsl`@nLjze*u#OE4Do4Q)s-P5M9O~A{Eg1uws+%sRz6JfP-&z=rUe?>mU! zlnFOs$=KGmb7DLoTWRmEE}oGgJKVif56~k<>+!Ht{7)ORJbR z5&W|=I+cr_rPYkXc)wgwg2U&si7$r@^d~V`XM1A-FUPB`(rne}o|ypb1HN)}!@?W- zowJ&kO(a5g`pUQB@X&WvnGsy4a2>wlWxo}`@jRb>QlMg?Q$b%mTQThyVr#$KJw!n% zf5E`S$;!)I5m$kv#mZE}q--%p&0t(1q3g4-Nn{m|-5yI2>+jk#LOQjyFCu0yU zl)#LtJf))4T%-B%ANvXcdZ-1gKp5E0WhAirPGMJVY4HH|kXp>1uBsv&mS&gqrOygB zQa=hKr4X|_mbwkUs0D-M+Cg{pNWbXtBBqc9hXF^uXH@ni%RJ(YcW!;ANqtZl^p|M< zBvh&53VbNh$avwX>9tTUsRcET79pX^=A%Bzn6-iU^uBe z<_AHIJIS#-r62WTx=WpnW3Bj&9%QYR8upaNq>^QG(*-wmm*KPszf3cKNn>t92fkSX zg|5I$N^?5q;o)iSq5Gj>d!~4-DGgScSt~f*1nH1xl8dRL*?G^PsAt~zr0kqFQI3vz z^p`Op=+G1<`$j3UDc%Ke*nL7;XgrvyEzKG+VtRH|wo~@!>YJKkLXZm!%uL-Q z6DIVb@dQvOU}2EoC_kcBqNnr`zo}2}<1YA37_^@jh~8OG+f>mOMBX*-U#v{{2G6-4 zOXcD+Nx}FYPDW}IGs=QpY}hRZ531n7E4~So12hs@g%6N&>g<5y=V_`EgblBX$F}74 zxgqSKg#QnFZvj@-wzds}ba!_uor^}gL8OuH?nb($yE~=3Q|a!Gg@h6kA_yv|{{r1x zbbH?K?Bn^~bN=i9uQk-=SYwX4)|_LG@r?VqpZkgGizBO(dwsxTEzYX^5%~7mrAKRd zZ}1LOcd$tH&%^rJahMDE59!!+oX zgoRLM1$<8-OrP?Y`Sxg}+Pnysc|BnU0%X&UyP>WaF&01`(Tr;xYZ*vXGId0g;Kz^& z7Z`{$s9;TS_;PSIi)Tw(O}l2xC>OD=4G_!9sx2m8j#ZQ(B#y*Tlmu+-fIo)J$z3jW zo8@9(RJAfPY7NWQS&_`zP&1hp>|SoV@Xy@PPjWS>rJM5C!rs-g^ukhwj1@=m;J80L z?MXR)FuSd|JNgC82HB97D9Y>lmLjqAP_VduTlt4~R+c3?8QE0{H4kmpOyAcp|MRZ` z^(qj8W^=l=a`rcl@+Xstc}onyya2eeJ1NiN+`qm2YIW^aP&hOLzJX`nAbFD$ohjmh z3%#??djh)eZ*mcTC2wurbAUt}B+|8@P&7e7PjVQ1U6A0grjMV3q0P<;t zKQ$>0`$nSB9_ZR$%u0rn^htd0-d#O==L8>rM52>+|qiBD2t!#~}c z#81aQ0dKq;pQdoSVXp4heRpvPEil~z$Ge7zCKnrzc>AI zVtciQ@59^#`~~)T>0{|(>5txw%yztqF29p^WDrdGB_!lDC&zPefc4V9mb>JS1Sm>Y z#HdTU*M#lwrtMKSz70tlaS5R&p*|?5*d3eQ@C}I17)#&DJUOqEKOuX`ZK)Z|y`=Yc zIV4t}MHv1sDW+Zy9Lc=G*p_kB{C_JmLJ2uwKNEF&PoB&E+g5YM%h_ZdJzTXMNqkD>`D>kwd-K0tl771f(07!MY0Z0)9If-mkKSY+4>p$2nf|e`LZZU68n<}#NUw#Vy#fRs|!(0{QJ(_MK>6A>I6r*Xe z8gc*pOA#^(=;1Ekt}@2ZUy$@qzhV&k9Be)ugWR2qJ!=nHX>8%JOSm)BgW#x2M_&60 zKVp4Rdc7Z)AWNN*WQnBsq#`=_*n{_ub_#JqLmN9WVGSX? z@E$(8_Y@Rq%!?)^3(u1%Cnff@xn`->(SzTTwh!J+UoN6km=iG$3gnjFidh~TlJ@v%vFWB!2e z8Y5)!G~GG2yib#Ab&-KGo(Tbl5@JE)iP_;5F|0dBdXIWBoq5KtRdh9)EgK^;Y#1&Y zNosQzinJ&uis1l8iQZ5|u$cJ4q?<#pJt*(hueTmkI+HKmylyj&a$_PJzJRTCb%J(& zt1o5uzU};OjF_Jd^B*0|M1D75KXGs24Cm!?^={33oty_;F=e6*va#Cln`d_*MmBt7 zdE;f?T#+zkBM*Zl$#N)W*eyk{=bDd(rXZ$XZ$680pJk^MXSZ?l^a(Q2d*){ILiq_f zV~R0&{qXF&cb=_kNa|DkHd(SY*uf{5(m;u|muvSUgTv;i;`6%=I_!r5oX zWk)aeq>zz58&?iQ1y^yPM-4s4<%oB8L!J#WAT}L z1IGy>GfrBHAb!|ge}ono$qk8f3r^oBG?q_kLd?eGM6+;-Imo?H-s<u;9$jt)HwstiVc6 zXsxf7{RNY)%@N~@){2f<8Btn#RU%!FoU`-c=~129W|lDcFYBE*n3p9Sy3DnyFR=m#j(s6n8IQl(C6*d@r(NUTX| zS#)4IE1$7fOn*30A>}KW)tjc45jNmFh;aUEWSIw>t}XpXF_w-o~8ou%QW)%}rebC=p=2%M4TcQ`~O z2XT94EvpLLWs2;*A~&ohBzzyRjAAOz^VWjvca|4B`xl#Y;7>iObAWk>_Rtz#8xI43 zclasw`1M|s5RE0#5?GJxTq2tMHNKd)w^W)}^~+U~^Ws8zfxW@$-NMhCx<4`1Pu)?E z*1GZ(^+kCQ(ga=Qo9Obi`5NVu@UjmLpiTaiFxjW;4av`f|kcoor$!CbQZ z?*#2GJlXM4U}5nj+-kqABFgQk{X#xu(zJqtgD8K+G|6J z*YabPRC<}tOTV<%V>4Evcr?~#!h@Fv74pr|gOfA(jiPFXNh=xW5E~^{B}c zOd<@el(**%-q~$X|j7YF)A-VrKN;M=skWS>(c2T zIUP2BYyc!0MT(t#asz|})8XY6H2d|_N7VF0R74MI5a6S?-_RnPn_G%nZrlt1w5J;S zf)hZG`<-F@fC565k`EQTT2SLTxJ5N3>lpPls*C9`O2seQZLfbKf)+oRT71Rj#(b{2 zqogK+7}M`8AIUTd|B#6Y1_Bmx^eBkKF~!Tp3}0;fG7^SXLHIyRBE6)Xxzn z|M`P#7NjNp7)M&+?#u^*nl@mQ_F^kA1b8!We!czWiuE5pb0|abtUYZg#HEUg5NISIK zVr^dL1y|AX(x2SLuECX1?!tGWdM^`f57UwXjlby*F|!Qf$yEhGjtfj|KNK<;pG5fw zgHKmGxMSzFP_g;0-S1<%`Dyz74$$wDdVnM$O)ZIm%!+{~)b@pWZ6TCt?+0J8CvVq$ zWOgX~pq+!Y)~V|a-ZF&xMrVlc{RmrGRa#N1Y;Q!HkjA{Q}01IZTQa zBw?!h1?&WTxG`u;=@HuVkECeEbk^XW04owy0q47J@m4iS^`mzR7;Bc|$)0^+zGBol zvM0Q(3*os8NmI1LY4gCZ-j#Pfe>yX=9)s8*udn^3 z2NC0DM}20?9$hU>5cfI6l9?Rs=>pVKq4-V$Mr~dhjHEiP%8hfdVpZf5@!gLl_hSWr zx}tlv3p2ydW*rqpmcu0Z7+5bJfzQqU2+U&O>{oanW_ksGQ0%?mS%)Othf3JjV zy?j$xZQ{LBhbaI0_sTwZlx&)82j_*)c(cAq{g{2XO)Th-q6fc>o-zVW<9A(kkniIg#l@b!%_M#wq6I|meV$E0N=Rj@$@;0bPF7UsZ zt>*(;Xp|&@GMF9m9DEP93>Ysj58nP?m zR>R0)`i@b>>jit;6tPw;Jlw3u@ld-jlZCm=!W) z^eF)W3%#`ClV|`s&4vlL@gz^-`6DBe7Nq!;hzwiPA_UcxZ2ZtiJJYo%q0G%w&1NVr z3l1KLm#zUgZ~9o7tDo#1JR5#5e9Few)Tt`xSD&*(U7_&)Ltr-tw&Vwf8WyDxsZnu8 z9L;|CdDdoISUed)1xkc4R%Ds-=&E;)zH1{Z2``o&5r{%RFnP8Q(){zjd3 zX!tlsF@avGwziUVzwI(%OG(aI&0b98!MgoVOI}#F8bJUffHU2uq}N*Ju8SSzZuNgh zNy*qI+hedM2xFMQ?Op9>0<8Xz{GWNPyz?f2d6>cZ=njlJaa^N%u)=CiZsg2J} zLaEKcimVjLD#SCg{60n&gi{C+UfLMiBMDbOAk;}k5*2qrD}f;peQxbgmcZs{chapP zH*t2Vc{mJ_ex(jtpb=fwmU)n(Hdx09l@`x1eDqwBG$;YHa^-onG8YWiJsYmTSxL&1F{t#_7CQ!(2 zZFMcL6M4tpc{~GnbA*(ukI4vJX^VQ%D}n4pdbNkZ^>2Zk-)V6k1U;Czk%N%bk+QyR z4Sb0}Eo&g9k~K|4B_)dV1fZG=o$CQaf{~De+w&fiwHJL?ES{C*Sdyd))g2jqdz{3e;66YA| zkNXblc4tvKh6bca3-Z(kP9b)3{Kf(VoA>uX9{ z({nQmTDM)VxK}^f=(nwbZw`KkSfEDW+VW@KE*bi$eF-Ts4+SrY-2|hjg80ca!D3j2 zIaLKtxq>_D;|(8c<~p*%&htJ-Rek~Mo)!n`OrRDFv4BQSzcDX*%hTfKvZojSU{5Ws z=U!Kp4#>;B99eYW z>cVgiquA+3gMGsc-{%RA+M+r+sQ{Q-M_^G#pN5H?jITpru2#|X)xR9LGf4(f^!j0f zc0=xG^zfmKy=OfoVkM+pabdxWDW5i^++f`gnFC#LVO+W~S($sp;pqfPbifFAX{j&< zp1nKRG(12~@a?V#fZOi|dPx5mS@YfDvB*~N)D8%hblw3xj6L7gDToRj-bAD*wk<^Y z`T%Hpuh%-zw^TTi6BAO|KM74qTgF!yct?k|Sd)pk00E$u*ED*s#owI~bm~@wdZ`?b ze9)w(3PrvW8&9sM2d}zIHg+1*6-zvjjlFUIy`Ohp(i#sGv2Is3b*0Y@9O)4Cm-&A*W&N4Bcf;1kv z>ZW8cJX}UnTr{HcSeAtO63uDurS#Ym1ifm_O7BAGXH;mXM3SanByixcV14B6sss}R zjwEqL(B1lhOd-QpjRK*qM&Dgn{I!uQ0dh9>x^=NZbhLWL>q_#~QUydod{bzfk7wIL zDB~0AkL7q-7!req@#wn--x)^6T(#)*(vJ&~$F0^60OXPlk8}n>!P%S(*+VTx?zN|m z-Ia}zov*TrvMP73_e1Ya>r{9nn;JEn47x3o=68k?%v9d)%Qv~wvY|4g%@B3Yg$E(? zAJaY%aC=S37Ht*BL_@jTsh}UfScxoLs%^Qxm{xUw7Olg^iisGn?!=5{P!SoG8KJ}f z6UpmOR{uGzSc)a=UQhp?v{?W&LDdrJZt>$BAcMJC1wlx@Jx-EjM?s|sCISwOMH5)h zMHC7-L?9MzGoSNdVzI1O?5hl1#k9t7*Z2PZ)$L$>Z&QT%5bsp8Qr{<$l0zF%j-J)* z>czwgyOGqw788WQ8p|O&*!=LAG_!YLUE9*&jT-vL$aS*)v{nrb3w+yu_Kq)06Z%0q zz*L&Ty2Mhn5pZVJ=wE>?$BatzkhL>dMw!GkN(>eZ`wevi5-mrM4aj8-6zTQJq!6c85@erE7U4oB$RIyJj`uATt{_L^MJceZl-3d+}YbiHb!nFH!0o zu2@dxb2KA9{2dYrao@^bhdVJ87Yha)*J>i!_p+C4t)6j|Y&|x?tNF0-OIFuK(F(Eb ziye2H)eITeogOBuF|1m#SQm7n9pM$t0oUm3VCw@Q9hi(;7qr&&jOxSzKsD%s*AAT8 zEqXYljHJN*anjo(=_0fkrtK$!W^Q9PFIJ?-w~ns^jK3S6!~FyRo7J!U_K(L$O20I9 znS#@+fX!c7lZ(eJ%JMF}1h{LdzQV7J#p-w?wtF7D+GB=p99W2dQwY%4>SQNX#G|WD zA7`_@e)rU0oVmde&fe)iq0YYbJl7amT}Eqgk=Fw4?1?g!d6L!y%@!%IpKD zgvv3MIZq~Hd`7L;mc{AjG_-q!G;Uga>~mZ$0pH<(Ki2H5lNX8HlR=~0js_GhPY$$1 zp+I23v}rWcijf5=3d}uRl+79iY(jblGXJe*T0sK#X=W#y$2?4pxNOCyj*&-}4=8ar zGd5=sErg7+W(6h3#jyJlPP`|)uLaNmNY1l6-;5#0_Xh_n-yPjt9a=iG4T#gq3V_?- z5qIMZufm39VNhifcB{I^o~DI)TY2|_41zX2gHsvQQTa3|w9G5w_(PBlBWV=Hp|Xg_ zGl@B|qC3g1$(pVL!22~t=P*k)S<&u}nw)bheS#t($gzGgmk8oV=T=KKrnSFDt=EAB zc_&0FS2n`97sBk$vW~pm@KA{l3Buxhl$1;*&j)+K&>BSj?ge5jWJ`)ZjWz74*zQsG z;F}JUgA5YIJboJDD!+9%nBA1$_ZM1>jj|8=35RYZmsOja8W$f05=9J!sRyJrqhQux zt3H|SAgC`8nR=f@s_IU4o~1tBTl^vb?c$lv(6O}>Wy zk8_|#-#{+z0#DmHJHB(BjQ?bG9q5XsgjTe`M7G6PVH?!SyTXdO%GV)kOwW-h3ENu} z?2$4&H##CAfb`Sw4#=xjlki1@nF5Y}9p*og!F~QnSAqsyps`PlbHFf*Boi`49c)y4 z>VzFzz@4Egftq-)%Fj$bQlbdw+~AzcMOB}a@-g$07*eeGgy?AU6uUnVT=%Zn8S0kb zg5C|C?bG^cCGMjNHZ8mK;xf8tlWgW+_#EB%9%({IF;^73)a;Um%%^wP3n zQJAtzsaXg3SLMS|j;OFD_8^5dv6%VeEU7*T2_Z6ia&x=3#Wd`MU;9#4?Q z(YkDTqoPR^SC&Ok_e=wZ`jK*|PZ$gz{9aFx+*mN- zJoauS9R*f|mBn^ew|M3UEjN-VzX&098@^eBth~|pm4#NWJ$XP7<8$tQbsW0bG=YgL?)VQ^Ags=Un^d-E(Y zQgDSQ`~l<2={drd^my450thvfk+ybF`8ucKsh-Z@3Wc> z^I|GCVmFT@2-N`VxZY5Fk9`AyIF}uppTS&{FY|tmTO0Y4ZvU?Llg}9kYeU_oYm+L| zQSq+18Dlf(av;PbH3a?#a~6Y=B~Lo50IZI$1DZTkD-`VF;9uYA^Ut<`3u=DpSx`y_XcjH`3^Y!7Nr)3vB0xdCN;eUX4`j=B? z=n#;Y3W#t+XdX9tc^PEA^6O6=-wAJ1q1e*N5}yCvvGsHmI}0()stc$Jn<1B?{%}aH)2FWDynp?I|g^>hIBERbs%(ezOyj z5Rnifx7+N$3y@;aSoD=^;w?euKh*e^3^lNoZ2pKWubM9*c59#4;bf~D!XU#Mznh)( zdnJ~CwO?1vNsM1hd(-`c!S5Bw!JS0YRg03!GMe3cG%MzxzQ-YW0D`d2US0D&!+dPN z%H6egl{_tM1CqCf)sFSF$(;kgF+OjUSNX@V2xHiGK9wp5ZDDmCGT)z3Y;o?7{@CF(`pUUzK5J_6G+HDjxGQ-P({Jql% z)e6Tj54I%XD3Au7ino`N_z4L->cz);XZH%ww}2o_=zF$Ngd51{XXdK3&_hlpi@OFPP}lA>3}{9IMvzxNa=#R1(fi`Zsvr5xzYr5LHYbTD`V(A$GbmoTNE766y6bjGq z%p~tQDo`N&UV*Fh#J0ElEF6RqNtUW9 zOL*dah%iLIeS%6b{J4{vfdr>4M4{-}zBN%EELdW%Z;un9k+G=NG~MaYbc;f7DI(iM*792x?7lMd6HFNFTBs+pY)hk?E-Ag>CLz z9RFFzqQ+Eb!>!!xt(&DhB*JIn?s^I4_=XB|I%t?$d{%qO2 z;%@Pxs5m%j>(6Egs);Jfw8@XK$0Yu2R=DC}ky2FhIVt^ivpE$Pbno@|U=ap>{wG$x zP>+5uK;ZYM=2AZMLXtH8AB63ZIhwff^c8}F#Idn()s^-C18*_=msgjKZ-W5yB-qE_ zHnvvRGDf(S+yxsE_AqU|BVgapO`77paaO>V=Nw?^L_l&1I=1R%Qi_^-$Ji z)&{)X#%6v`ge`f79#9utbdg%?oJ2{ zjep-*v)x=RYg*tSf*Jq%FQA7v3%o0?NZpBZDu=6o7618~oee~8{hHwE)<*pg2bA$( zkY8H<3}{k4fJCs24o2=x2`4bK+||B!Y->}=m~I5dnYL~`Ep*4Q(uf9^y6zYhu%^ps zYk@CLV{vcU>-%cq6Wo5C-tAlJDMqWPr%JP7!y>Q^sYCQaY8!6@&^+?%_c_*e4(S5x zLs?`aY^shNV^-Yp*xUR0q_EP~lVvV@TU%L0Dv~NRtvTWrh4zKFU$IFLEbaNvmGD@1 znm1ci)$guIYr9Qx2LW-UA&ufzC=kw_Lzm&*n2d~2_1xM>jU0`fd9s4@WGLhfPg9me z+HP={Erur#``;<;dUym_E%ItfD$%hbbwWzg-%Z9S3l9*L>_brILGF8-`EJxpjt|An z|ASbH)C*x*5~d|fH?nBtbzRZdBE7!|Lc8X=o>SjwVBX?a55@E;uPQ$$*Ypknr`#II zwJ=Ow8dPjF?kZpO2Bpao@*y8Qs#UMAKYfrX^GdC`5q|e7QqD#y6;7|XJt*`nC62pP zfWsM!bcteE6dikrSdlcQRG#uqcmI%9fF)EawUu4e_S<;!Wa=+qB(=VFW_HnT6pd*5 zkD_uu3ehv0r)rhpX-GdUJy)EWP8T-_DQtovp7zlse+37 zs4Dm17b_p#ZCxye;mu-VCs~Wz+>n}_u}+M~=AA`dj*h4XD;pX+J%Nt7hXR=Dn}Sko z&~9nkFP9+UgVl$}K-^lXBW{DZi;(b&#&+or8V>+KL^> zu5-7R`CXe>cv&p&$Kv{DiopvfN5<{^W8+E_pj_=E&)Ud50;dQNW;mpHdz`c^_>#+l zsZmYTkM063N;={mwo5Eu%0J`NfpI zuvUSq600Cm-$g+v;D9-_+mr*n#@WNw$0fg~+(YP3#;F9%dzSS8&k+hVF392JqQsH|jBC~b9DC*6iZFBQiPY_U-w`Yk7S?G8&Y9 z*ENmVwWK58nz*Xi!TQ!F`!oKnSWd1Pxag^PY#5{rK%(yx!iO*eWP*}mC}G2EYY!IS9Z0{QgYr`TTgZ}LGTr$f}`9iEcVTV zPbO$@HMmAS0sf8h&)aJ=!4x$F7cl z5b^)(aP7|o9?k}z_oIT7{9k_qXlv~|wIHT--$B2-9w^Vlpd7F4avLXF79=5mv&XegG*|P zXB4#YHH*7Py`?n7vi6_SngQpt{NC`#9`px>K(x-VQQ{Y~6BPb!$(_aJc#FitreKL% znUM-olEwUXgvD-$DkRyVDSjx)^=p?iKVuT_6CFB_R%_m^|5Z*$ccW>c$rVQ#a2Ca> z^>t}k%BVnE=<0Vp3z%^d!b2dL*1|%o7K|@o$45X01*F?2O^$8pFi981dBjjl!F#$n zTXQ6&1n9zPNE-2MW&+L9?gc$f$>YUIg_2y;uFBPZ^;m(adRA95CP~wW^opTV7`3?_ zC`z4WPKBGq=^dYPM^q@yr5<*8OE2PXJfs|MB<|WmGq>7NAyZ$#3sUPj9saIgx&=P& z{TOS#A>pzmWa;u+pzqJj9N%+v{KI$TeQtOB+FY}V*Z;;*vuN;IAu%U^+0g#*B=W}# zvRT(s&011x5210EkWEEMD@Ui(3%nip9H5_Btab|D(4`#4;h)3$8AVHlJ?kg#MW`vGQ7xZ~$M6 zmFSP~y$bI)QGZ0g&Zz+AjQOFUc&!C)?cUxj+$i^dB@dj5c8`iP=q!H6%CkUui+HYw z_QJK=WSx(_#p!qM>&1fy%Ccu{`Z>>ex!R+!e8kptb+wh&lvI@FwQo5OzJMX!q?_2H zTGP=52a{EPF0ve*r}5uW6apHj&3&%Tsh{?!Zqo=dd6f6f+oezCHr3K>(c5R-5?`hF zR1`=#yCTD{{Dx&Sn`N+hg6O|uYLYqU4HvADhAVg_9(ZJGxx66(xT>yA{N3f zObTDfb`_t$>H=N?hWFooYS-|uXz7}IQJn0Trvn}8hEMgv?C-y|#j|&GH0eXadGr2X z>)__RiECqH6Qv(dKXB4d;Mj8VG40dr*&J0>Rvle_V-{Bbsoi}|`2b+yuqRxa?EVYt z{kNs}za;`-#t2B&j*v!s(u4eanE}4`EsO4^&zAhN?wRgO&A~5VuLeHz4&PEqxKI+1 zGq`(B3ks-5q*rFHdD#8?3Cm%fte$4DeCvru&o8+4J}42#k!tn(CU2006g*@&M)k}8 zn0o#%rTYt}Cs+I0@7}s*)Nl)U2-6Z6Do`Adnb`jyC|H788z9LRCP3?|p48O8w{VG~ zry?DJ1YPUCg+G6dhI0~sF8XlfseaJEy9DwQO!E%5y5MU3QA8+a$;&gp#u?t2X`U?| z#pbw$#rfvfhVU1#=$n1%r?Fdlq(0p`e`q;fAL239rRg)UU&*1OWCc@PTP>$p)Vg9X z`+m;tSkB)f39eL~x`ZWKmwmQ0=VMw}IfgQ*#dCmk+>SMXZcBTsf$^q=URpsvzvql< z86>TR#hdFEGLUn$ypi?w(bmaPvnkXidTE9J7V&PGVptaL_+3sFH!bKflvC3y8m1Oz zG|Kb;s40dlHG7RQxprA$@<-ppE7qk^t=ZPv#NTQPMJbe|RI>({*8V&jwfIPXn)I?) zgOimkP)_dI!GodVSzGjlJN)FZpj0Xs4~{KwikW-uNo<%XN(qPlOxyC;5>0MOn!GIq z&D$wpzIOPvAh82km?g9rc92AZGm0+-c>Xcc#=7hflt znW^B#;ChaPrnkpZ_pmG-gdV2xl=T#)=Wp+BI7~0$4+Tu;!(BD95ORBTtvy5U zxInnzIKI}ByetIKt-o5u2SXKr2G+ogQyH?xzQhL=)d(9aT=8V%(@jH5`4d}@lGq4n z;woKa`oT|lH_Av?SY-T!GFpe1w#NX|sDbY7=0ciUz(*u}ysD!OnQn8gu8Z>{M3=T2TcLjUVPDaxfL!h)r4Ca>%4jXqq6}K4|77^U3Vn^ zs4PUE#}N#j6UXc--J+azt%ew+`5B3Z^kGP}EdG)}1Ack#uzpPgwR!A*eTw;7wi`A1 z7I=!M>HF8AAJbtx$!N*2iz5`k&E#dtClPK3HhRVc31&r-Ec>z~ksCQ`%%oqyOn)Gk zeF1a%dNq%LfepGuq?1KCj~|R;(v%7ipWh~NuV2VnUIe;+70$cSMY5!^d2OD)azsGW z0fL!s|J-ZUB-`s~(<53&+RAH}#n(^8?7fulW6F_&Kiv7-qR+QQo4@HtYjS0CEY`3L zxhApwJpt)o^aawQhOJhWV7eu^_64jJG!3t@1x)RA^_wZTy+@BE*JY&CBsXOCPJ^=nj$Vew4ZH4K@Pwr~aTHC` z6WYec6kd!&It(j~o1ZsJcdjYEf4ZZ5)&SA-=0we3AFJNZMTW?i)FXC@f`0BByfXPh z8zX3a@k@MbAXcus1(>TqVt#rzH?c&+y_Rgr%A%7s$9Fa-(_g@(H}5A&LKYn+8cGD8 zv0`vv)sfDP+dA;;L0}K8MN;oToV#7V2`#D9^2O&ORfc+8mGD6*rqa@`)~D ztNB$ebLdD~{^b5?>e3UfFf|W5PeSjQl`4FsqAhB!H}k-s=Gn>$cs%>xd7xM<%)x(EhX4P5!ny`35A$rj0$n(+%jPN==;88W;K3 z_T=qJ+qtYg*GAvI)5-SxF#Y9(t{YOes)bKeMsrWAlGeh^?t@0pOG}i*qIpGHi|wOH z(8Qn}GCWU0r|wz7Ha$PBz_mK7tf2q4;igjVpup)}$wuMF+9s65^82dQA2dt~EA#X0 zT8fMFZu$XL7U;ew%CRv9@ydH%ng?|(hXhZ3I~>%f)u-%YBFn}guM0G6If+>Px{rZNop#U|{W<+pZP?#Zkos9eP~O(xd}ux<+AqK0$p?RP+VxBf_^p z&uLJ00FXW}j$4+y~GvJ3_b4gn4> z0R9E+(+*YT6|w#Qtv{JFcHs}D)yzMC0qZ(Nc*yurA63%&Ic~b0IQ1%8XcMHtZ~Uid zjS@zY#9Cne9l!J%7U?Jed~j{|Ep)e{ZS)hE>KfUne9+nyFiKE*#?;~x65Xq+OO`Z> zU8jDf?}x=P$Gxz#v%)W>Sy?{}EN#=g9`A6f8`u>s!;`;!E`49A*|`GenVB1IVGffk z$0>A6?4#3Sz-ZV+rckAks^>nEBYEAFzuKuQ#@! z4u}wBf-gk|2Ip`SbPx+uL@3tGeF}`4oai%F#l=2VOrU(+x@1xQwviM%72TV4*DSkU zB9q@6@HEZ9lyJFOW^G=nG}4I1M4JtNSw(^OGwsZ{Ng|p+2lqx=13$41&AZ{AQp3+y z?)}9dyQ*VXwmC%MM5+Qo1C0(zg3P3e7H1Gfg8G zwXk@{I0J^l&jLy+WpxXPk?#NhjsIVHHL{Cn@lH!8ETQmp-m))Hy65J&1)7m) z`@F)w9(W{bPpf#|&3syX%C$h;6kF6nF@^-uOCk92^#(iYtTs(^PvLYXqv4sxG2-;6 zq_!URF5}8KV<5M9JDbe;|EV&$mXcCcslhKd=zhlEKl7ooxValYrDwtoIy zsjQtVtt^d45!P+_1U9?<|Kfid?tg$r(!;iYg>p>9-QWDKJrXcPY-UDGh7U7)E;X1u zwT#CON!Z@sjOyO_@BRaEIq<-~lHZm>&Oss#ALfa;-#h*|2dXodV6o%lvA=v9t&_Lf zZk_s_vlIg(At)s4{MqYiKV8V;Ua?kZ%RaCHBUqJ~J-SKy`6=d;DYI1|WbWO9Y9HcP zeL3`wk7mcuMNoLEOajL7X12@apbdMtmPVHvGCIHMK&D%fum zEyrC^gFG|HRbP1mP~o(hb%Ja>UdEI5s;^@UIFicYT+a^ye=uG?!CwwpPGCz!Wgv}V znob--UDuLxipTLT+PSYCfus<)V7}FYhAHJ;#S= z=YCRpN4Acbp7FAwoYPRYrV{lu#DNPanLC%D0X5_n?^c^tpvwRnUsQTPgHO0CuHqc! zR2*wlkpbI=#`Fk>*PramZ4N(<^#lz>tHc2J@NGluHQeRugzL5_Q;`YPOxK?zmvDyD zY>K@F4boawq*qKa%(XfNKmo;{2KAdzvoIH|wIC(F`G%P=k6!LQl}tIuJmAT(@n|~F zQs4LMOpGhUnuHErE&seMR6ZqB*oP}s5&j-$Z)@*6Pp4|m=bdo)5$&8&aWzz-!R|G? z4wk%WC@k@|W*1r--2;2B4a;uF39U3c*ulYtx!LxXNa_H+xsZ2jya*yn3e>?-V$Qta z4)wa#c>V-$=xU3v!Qm2EnWwCk}`(+f32;_zdp_h}Hj(T3F%Q|O!cGD48}Bh}#&%hs_6 zI(L#B$o62IClOz=GSut+c=9t3ktwDKG2&Nwg9)$ljYHtL0<6M!&qE5cpM(jGIs4I! z36DIu!;*9be_%M}1(HC-uyQqcgDDe_BGFdtZ%Pwy9RNB+!VAsHh3ey`ZjYQLW&9(T zc=JoS_gISqd6y%fsWIvA`L{e52rW}o{ZO0m)cZo_`>)CAeB#25`~eMFzn~sfsJv}+ z>O9>@6VI*gE(c(wS?TtyV*N9DeKVN)rtbR!>$S$_KW0ymepGuQYE($Mx< zWj{X-Q1^smfP)TPw3YGRg)_SBSiy=19D}46y47QvkDCT$MGdL(k6b5!X0~}|T<|97 zF?kP(a)Em~bLf`TQVBb5<1SIzB}zX&#h?l;k0HZ72$M{RXyq zF~;&;4r#$^cbF5KOt|)kh%SPMsv-qdf;CSiJ9-Z+`A0J&xE0H~s7%!i?Q9Sz$}gIr zU)1tUcqp<%l9SEX=S?DWsNi_889eg`Z3Gb_74sP&~^& zajuZ_g6=l<&?c8qLq5Bs-MqiqbW_WC|CS6E-Cr2(m9Nb zllRZunk{wW?=R9TDkg_2Dj&43mcb1&p`DmcgImWPz*C2@uy8vQUW?TFtNHvGAp0 zwnR;J%t)A9!JJFSm_v40r3VA{r_{zF?{JwXyN_9+UTDtc8M*b`OVprJ6&8HZkY%Zq zj`hSh#2&jA^YA?tr99M$86JQn$oYm3??Y1(TVJ8fmi)Mg^Mwyc zsmJy9@GYKk12V^8Qiht!Jt`SqsP7zG)}O4?I4O-YAR$QibZ*Y`5N@k3HBFmu zwU>7b;is)DsdUl=@*lLsn`(09=xe9WrS3HNCI&n&Y@r*2sVN?pJr+Fp-0Hu0CCwrE zIqu<=;#whvBv(5_v^aN2lr!pQ=Z85~7#w&T6b)Hk^v}{vs6I|MJQwxF_J{0^!(iEx zfo3U(&T&x@Rw#k$#@3;FtEL_}+9m~^dlIQ>?>^nAPUuD18uFBU4~K@<88tDi6au!^ zz{q{!3z+z0{LH1Y!F_7{C^tS+DkW8B&o$L|00J!76xT`vMU&E6ii2Ut8E?gu0bcwk zAJyEUo0%=|%W^BEwQpk5&S9scGs*6Q=WytPBR$}amIhXIW2#U|8=eVPF{Yjw7M^>E z^(q|e_3r_CaTenE6m1{0G^*P-ZTN=7*aGi5Ki-f&nZ2X@P)wr{gU!5&u)I?<#LgyH z3G4-Ju20*&n7ee8F?5=buX?=5t%8XY3xU(9b#U66m|)~maL*o4FE)$TxSr8T+WY|i6*eSIl zAoB8);@*AYkuDyy=&R`Sfxirta+R-Zbl6X8v@5o2Ev|#bttrTjX>*MS!>xp638LW< za$Luq{!H=H%V0Cql%r&=0i8Uc43XTS1!N^y@jArq!4O)K z6C3Ynf41!SoDxInW!c7}MaI7xR_7qYs+``jwxqB1<%2NyzTC;tFFYvnHrC1mnOw^6>c@d&;2H<)EB|D7J%YoIce~?!#~X2PIgv6QQyF81-1*To z;vzr1Ya7K_*HrWtsIQDrFQVL7kCExs#8&}}v!>LpIWF!nvEzysC3-{*PPwN6>XwBl z8TdWg_dH+BGUU z)U`%F&&U(+KD%$v8)JGHk0LmXB4HO6*?9G>WCejc-HtTL0^%Icup&kZpITMF*QDO2 z+dU-kV7%JP6L>4ILh`dA_;%e`sy`7)FFM?&RuP-2AfQOlZ>3ZO0)~vS3DdncS)4&t z9ve|plX6>T_Yg50sFSo^#ZKIx&&>u}Fb4&nw|byowM%kb;cpAS>Mv?RZK)}#6lJus zu#81W$4~oTtIW*TpMq^510zD*86{EoE!w7HafkB8S?ZVZY|C6-qB@)5#@sIX;I!g`2rUH>XH#eK%0gs5!oC8 z6uHOo+zD$KUCJlgUyoRWhQc_c;t$k(?1uj|brkkszw50hL%ajlnM-7Iyc|7vS6MQjA_+Sv*GdGJNOt^?V)4-cC~_A4m?P|6-cS>lDIO){!pQU~u6dcAG+I zH_N`TY=X-`a@k<>t6ZhF1FQs&L$}$bKKpBvTGPoIWdF=^RT%~QYP%zdoHsrkzi#ejV`}>rX@}7Xh}r2LtT{J`yJUAf7re%Q5u&)Kat?$LFX~kLOKi zE{4E=b7KHiSDscfZ^YA&BDTiN^2xQ*G;dL*(b`6bpR>cszQ{uP%VpOj-y}6ydbz|bQ9Lnw|Csv)V11!1ycdJ*{a*)s(ARPNdW;y%`OzI!^m-(t zvGDcYqvq)jbJ;IoFJ9x~nO#{6J+2k6$MW3BOyM(bkAoYa@i2o)ds~y_wHXxaC+aln z3tj2UkWut}Ve1a}G=J5HSF=N2>@dL>k;}e3bEPYGbbU4I1L_Ldts)3?3zt|=FHE^D zYO+Rob+{>`66Zd2MW<$^6$|y3ILjr4g^^~YdTq})iAF2&NIjCq*rBa{bs~xLVaGT^ z7d~<336UOgj)(Dhz3&5Qq(WfVh5~*-K z-9OE!?Z^Y#Jig7YE6TS_h%Di-mndgZ6D7UV$b=_h;FX8ovIkYgmJBV5D4s824AZ8E z7BAy0?^Bs()IEiDq4Z;dCP$iCA*RG`rV*=teeYma!zrL#9y))uJKH6lq#$3?6zu^p zv`zWE)c;V4wZn#{7$wU@W7tG87FI61K&J#owgC?j@q|@cZGth+bc(TyL7Z0&(LjZc z6Vv6e%;;gxu$Ne~6hg#4L${=sse%o<@D@+FT^tVHtY%h}x%KkXckC>Yas;mQsB*hJR>EB`G=4kIpaGihuc(iziNL zQPUCY4m0vl!H9+k!!Xc4he>t<%g}s&oYWwDY%2l7>HuaOdqUp5e}U!Ai7VTAdF-pK z(wtM)z~e2LhosKf6&6v-I~PyygHp!_1dAw?^DI+i?W1STK_YDG$GtR$*D9ihpaibngEt+I(x+`r<^vBHosm|<(8}> z4sZnwd7mcS=Yfhu5)t8PfNj#5R#Y~^lg3WaWNdk4I+(7)TeK5gBQJSZ`6Y)G^m&%G zYmFst55bGaYgoea22c6q1p1Ow3g>g~(<^yoHMP;4ubk4npMC|S5#~)~l~2YN5fw{w zzTfzUSM)*m#4fH%>Rjxrno3X2N~(hoiNOAZP#4&aY-2*Z)OPs@b2J#9tCtP(!e%q@_!drv$Gbyo+ly?(C0~_sD9Ml7SsM;>p2)3AYlsr=APQUOZbyNc8%SpA=Ww>6FmD)vtfuT?H z+LQQQzAKcg&_v+e{`jE$E^^~jJ1tec*(Sz`T z5Ur>FbP}n#NU*Db&B2j0g|gMx=#@c%*?W^E!0U_h#x2;?O{3)K%r&k05P!EFjsW_s zFLLDF&P*Fpv0Sh$)$5<|FnpC1b43L5##S&3Z zNm`Hz#CpSl@gH-rg z_cnvEGQUBMzszMMhJl5oLB$w~FL8teeDA!^xG7ZtVZwM)KU&=rJrBg6;px9sL;#N) zx^a~%!WUM-^oVLom}&fVoczbBnFsb7>RkBmrA@z*G#HM%Y^qqkqo;3zI zhD&QiJ9@zQ$sZXVME5F-u4aO2R{Vxpz#BtB=1^Qu^dGIV)eL9Os?-_BOzMND(>8cba%drn9wB%+)Ojr@cG(UMa_V0e zg{Ehz41BqnMoJ<1qU>n$X4Y=C!co)9_Q0uvL3Ou!s`hS^QpUb2-7Q3BHF|5AWHq)!1T7~#;xEHElDUDTMkrQ}T41hQAJ)FkwX z8B=MH6jj|5u$rz*Qhh6h%c!3jaxZV2V zr@f#Md(wV&?er-iPsKnkv2#p`#4%KoGK!=nBDs#>B z+pFAHv`EYBY6^Fw3Le&2nxn%`uW=Rbnq{`MNGSQ=`Vqgakjy|xdT2LixY)~0kL-cEzccHC=~yYl5$llag%2g8{%9bfd%H$H?AsZ3BW57Tb0x&E1L zKp}KM^WYPpo~Dj(iM!p+xvn#kq;^miMG8b-|FzoQl6CD%)#Ujd4PuTf-ujZ|us4 zuR(n+hQF&}Bt7$~<#oJ^1iyUOn|w#(l5DRk?oYF?sjrk5hts4;;P=4%QcUsMqt58i<$AWfx!S@a8YM68-xj0I$PiS55mr+!Tx!1SCf~OKr0KZ`* z+UAH;m}xFOXjpktLLJ8467>0rN~;_~Bvv^&~4vKKLLW5C(z-5R)+$;sgLD3-sT zW5C)-{ZmGftu;@Qr34i17Gbq;BAhgf8H-ItwOw?;hl z0PA(zDfmn@QpG|M@b02rejWNr!5gJUojcvU(2fOevR(!Q4N$N-HW&dv0JUo*eE(7lc4ctH`XqgY zr3K%qD89w9o*$2Kmm+dfi~klpaVTxLvnk^!kJl(QdjmamwZW+6wNEK9_fo8{iY z6OBp6abZsaB25bKmuugjlZufalu*mbT~|0b6CR&G=dBU&PkX}Z*l*ncXrhny8q#}m zlEU#Gz`iI#azRPH+Rx%&E~XxMBXt`~6mnles#D)DQA3g$d=ajqYf;dd4tp{1Y;9|K zyVYd5uO9A}OJs@kQ-ZvbKMQdUN}=1?3q-rue1D!rTZ`IJk9r_RzbCz0GnJ39hXHK`X0oJVgUHCBWT4)s`n6@`sU6g(zoj0s-Mp@?{9%PWtdrcSi=W01I$R;;;Y$s+_qe!~a|?th|Wp+ZJX z)SendBHIdvcmaZ?(em$(rUmeArUIczAjxz74DjN~FG`#fJlW4JWx*oDT^BIv&=QlH zwG4($L9`=c(k~++vtsG=9}4^&l~gfzf$b z`~laL*UEYT`x`J}AzU|?%D10R5%I9N8M%{qA^MsO80Ys@u(Ph~X|-&i!D~T;>VF?T zn1!?)sNj~x&0jr>N#?)E4Kh?WI&d9h@{$KQPKy;reC937H-DsBIfcdzO3EvJoZ~(OD1V^M5D;n~G;=Ll}p#X}fpS zUL)RLbBtStH?#Q{@c&2OC_G5`X%bBIdb0=FxGvSp#htck1Jp5Ry-kpgKVZv#cXFxe z+Or*0xiHMf%@ek(2PeY7zOxPi*tyT>uBE;33v>S*4(@syb0!aY@v|)U=o(+>V9< zo?Am7g1$EVE^Z3AgxIWY6u4YgKJ|0qj~7_)?US%xIL3Ux=C1-IL2rH4p|H&s=A5^s zQ6C|qA7=jy4?|Bnqcy|qas34NBkT_msQnme`n&8bMkl48Jio+2#tN0?IJQCf^3^f@ za&-_%RQ>-42NnV!gMt*}>ZQURHcnW@`;bL#qa6hW$XMk2WH$hi;#=4y%|8PLviQMs z>!H%e9G;2RrcUf|O>D$oSCP})DlYz|_sYv<$M?WH5bIv1Z;k5|me@Ar0E5_wtRN`~ zmpoR+gZ~9=wNS1Cy{hatqYO7UT12$i`aZV3!f@7se8Zvb+WT0Uomfv^+Qe<@*=;Wu z=s?V(RH}qy5}bl({(J0+J{saROz2yuXvW<5ESB#iq>w`}y}Lx!UCq1PwAD1>M8rK{ zgo?t@6E8~)qyX|>f|p-Xo7D&PTFJEPj0euW^?8wg=&|K~ef)BxYQ;$sK!I~ooUa*L zQrq8aGN(x(Z0-Kw7x1=F&P35yr(+`7SD8Sz+Cv#MW**9KPF{6b-AvvpFL4_lMm50@DfRT2)YRV<)8V7$*#e$HfA!gMSXt%gJRIl zmB#`xcou+4{G@%nb+COLqQgByPz5a={{F?B4(%gEMp9s0T*aFT6}F_^Lb5WON|??! zXb`Dv4fK~awIk0i{H=<5RYPW= zDT{>`ljD;%(PdDnRTz%wl#ry8-zYg)uBe^2r3x$?2T@PXn7hX9SyngoU$D&U7`r7O z(la(o|0bv?n}D^IzYbjeltqcQIqQ%BAGP(5rT^h=lbE+70HyP>YW+)j`36$laX;yT zbQS6lmB7q;ykmtLt1aYSp@-dmZe!Fg=2(sIAM=8d~b> zq4Akl*76xDF$2!|UA$9dCG?x}uWEg#!LA&`+8@Ae&&U2^rP$wEqOU^f4$k?OV4D2P zFQcIN8bJIJ;@PW4_gCx4B^t0hf?sJ>eGo+-Xp!10DDd-~1K%G65kX%&Di-t{Bh)-F z7wS;Kjal86BUz~?HsU2Yq&&?V@+6T&g0(o8KyNcs{ z@`$z`BTFVSO@7|N<>NsMpLkj`EQN}AhEZN9!YzGOf-qejlh2r_Y~(U7Q#UfC*SK%< zs_~eMJ+$kFvI+|67{}$vSEdfF8CI7*9$0>nCLTp2o}zEgaqGp*CB)np`cW9cx%7lyD@QFY)2HJHi}ko+J#;5h*z84#yM}bRO{$Wz(ly#9UeGG++8) z4>cpZd~rC}X{TW~4$(Teag?ml$85Ob&>0(}L6D=_%FxzbL&UtC3c4(bnsHg)Ht@!k zg&yr4`tPCSZXV+F*T{D#5j1e81uZsDh-*kopG?Y1twmYwLlf}!> zp)q&fuPnX0hE)|uNymp{(Ih)B^=aRdy~Zvn#PE>vn^^LBsOfI@xgpnaP!qSFD)Q;!H!aS9e~G z=w}*qQ%T0^IS(|^9oG5N1>RZr2H(*|!Lfy}+KLs$;mR-LyjTb+g7JFNFPCt{jvcTq z1q#5v&RZr+aJX^~D>!`lf3ye;k@XOy9H_HMibwKna5s!bWnO$nc%=N&rsmW2ZdAgb zV_8^pT;g`PY@3z}he-g7>CX*KZ6xAU)61osdlcDSu)@br02gmqG4&wQ-ev?1#S)9?vMx{e zVwM{w$oA4GkwJ9vR`TLwvTbu*bWa?!1jYPnW=M=q^3WoDR3f#6==&F*;(zY{{ng(b zC*6(%d7}1LPxJTdff~XcH4S(bXhn|GwQ!Gc1^bReUGONt|=q-HJL5U=x~hP7#cmJ`SjS)xJ#HG5rAK-emE5 zWpLfYWo?|)q;UqwDT(1sLWcM#x%fnqcRWVakZ4Q*s);K~mZher`!Y~+mEhUx67|DW z^5ke)QT-yeOGxX;dbgues=3^B43{hyw`y1(`JvKIvEnsHIfyZeD#6<*&OF99NZBUc zii)K0r8rcn=*F6&mwkqoH6;_;nZr*ma98WE+awnM`Od-%b6js)K#;@FUdbg#(UzR! z^?$Y_Lmg#;#clfeqtP>?$hC^QC(eDKl!=Klq4x`UgqU&q$7mNG81G&1+&UDoqZ-xl z{~B@bsgnXqz1=WBPVVUYd7_mD=n1lMM&mx96%zdz#4=98-SXpK%FswbPgzhcEc@n( zV?kKILPF1eb$YjUmjXj|3_u`jzgLf?OOfX#CWD%^;_26s3b)eX}=W91aQm zki$+Z7=hND3mytM)%(_`VkQ%%bzMX$GPVD@+N?o>W1#ZFrZb4^d59ounso~$!n|Yc zbuN?n^ul`7P=TiHzgaz^)!nMuJVyAm5bv98(=@)s4}+|PFT`m_dOdft(=xF~cpyr} z?!%~36H_h>RWfN9Sm#M}j+$`S{@l^q@+j_OcyjeKC-3K%@^~pBM_uQAa|wh6^6tP6 zD-$ou>QL8DE5=rrNf}=Y(#JJ}CPywMN6cxZL|cOV6|ay&yCN&;%R>q1zy&%b zG=CvxV>1-u43t=ZLH`Sed@<=`u^;H}0nsHjBN9OBe6e@Rg zWH-AOq5uoJnm=CN|3%S*Q#bk5=1_ao_Pq_fIKTeX)@8eLOFGSYuIm|spT-Y51VWv;T#WzR<`X1oQ!k=> zJUq7^&h_PIk>kgRPWW7#NFRTSz}H`~v&5JEY5M;Nq4lS*Y-^EI>QSc^*G5S-F)Et0 zXbxh1s>ww{$Cy&-b{O^ltT=g~Sy;fL5T}A&Vn(Ij5yU^PP|PR%`RzWbMv6aDr84k8 zDW**fD^&!eavPdo{WfG^pVBSCHYp`e98DSe$L$bcm5T8+L4o5kS=uCS1p03SGkg6V z)+mr-o|&(9Q6eR!yE9jgL-O8w>x;^_0@DfegvWT=hB zZTU_?jW_qY2F}+yZHoPpPbavgrstXoix&JhH|-8J-I^^@=LL!Lcpjn+piwN2l0BLb zFMLNGX_(YsK5Z}`2W*nu+x?xpY{7+$HHSUUj8@>is2lfdy;7f0ytA8|DhnWB4i2tq z;%2PY&K2&5otV?5|F!T3#Cc+!doi_yr#4g_L#-N5Z{1+A=dJH^3LNTYv~>E@;C@9+EYmaI|oT)yh!rPdHqUlrUX@e}sCX4$f+U|O{Z z6;OHzy0j6dT%d3|OS%~^k3k9%u_ch2#rZoFNlY_eE3Kq%&)`WY`QN4en1adQD#-~T zg!1GN@5_+b7U@Zs}}~5Uhry>bI7C zvy90whb6rr!*K>R-J+`22G4T5@}cPF5zlOoy_~~7jgr^L^xZoNfe)k$S!^M(!d-2h zYC)P=TLf7CIj?>54>gnR(A9zSRP03!;SP7J)*G)ft^|eTQDtN0_je;zZ`c2JhVpG_ zK5Sh%vj(>B)y_$L5-Iu1Td+?WU6X3wExBZ-K7WEa(wwEmarpd-U!?_BHdA*h2n$Ot zE-0n!{8XQvEbwa#t?p34mE)fTv&r zz;)2MREoPO=lV1jpJWruESQPJ`8rht7dI}*v#Z2~5>kR3f?SS#b)4-4>4cXD0USiT zJ8e8>9bY4;k&iP_fR(!aC&_;P~IJRi_D#xN2@8PL13&K%*qid;U0UGF|<3IYQ zkoWul7*~y0ctq-kG#~qh_IGx=iMd#pW?A`31uxCVv`2`*vd~KdQ@FzFk_A#C(WC4F z?aM%6Q3@xoeifeFTo0Ue6W{1y-b0;n^6>$8mg#%a;(5Xg@ieX{(_c#j3w=4iRAr@K z_sX&PVjq*=K)|?jpB}FQ8mLz;M-++9;tp{xG)vRCiatb+NqEMo;2vW^j@w;H zw&&k%^M0P!Fd_NXB%?@Xe0BBWgT@B!3YnYYpfzI4>m}D6_?JsvX%i=)qBFCfyK^i< zpZXJp7JNKF%2Ecg#sUxl02m!arVsO!p2;^MU5xQlCqn^!bZ{u@UPk>%>&v>cXJ$oNDt~9DK(^g?{E5~#AMxGpZ2@Vx zXgW&T_=Mzn)+tq}u_czkA2#Iq`ZRT|T2Ik((>CPQik!UoPXCmg?DK6i$fU2`i-&^- zVf%o^!Ds7~J~3KP(O|*zvND`0{fNI+Q0dG4GN%az#U(P`r?>P%xv7X6Z0t(`e4wumajOZ-wFZ6m z-gbZ2v-so-Qh{HIM}3&?=9v38JO2YSe?|cR9lLUFA zPpAoeFE`~ZB~)N1hDVRb>O(cbL{c#0w9er>vGhBu^q(C>-fsP!Vz@W0v=IP1-Dilg zSy@!r?%l^AjhN84JmJD;re1{y z51;?;!vTjdPsrQB7>~Z&b;&%o*9hT1RkC&IKz6qR2QDZS+)K`2l6TSNZqsvia7YZ1 zwmxmWVsE`@y|E6p64{J*3h!p?^kTr18mz0Dz1n&K2XYQ-V#l2t~a_W6AP%o zI;1<@p*=z@u0KLdKSFF4;u5$B^Xgxo79S_I z1V3?t9HDJO8P!OLw)n`aK#!qo(npB;u1APcupUJW=gQ7n&g^RT$ea4Kw=W@jFw3bC zKP%XvLL_gqvHr@>XQ3a6_Tp)zq!+CBk)8Lx_t^qLR-HdZ;F8Lv;%PcnWrK7Y0%#|@ zGNcTkd%JS?yQh(m=h{P*b1xcuL)FKqHfr~~Q-Yo^ZP@`r$3Gr)h+M4L(kjPbMxH|E z#%;aK+>t!LgZ1~#Q%hg5A74}K$?K`f*>EslYNk@k3(TiMw16Ob=% zEc`5Cev#OB;Lrw@-}tibd1mD|O@BFc&(d}ZnwIG`3@lyCcOmffHGdMU?R!l`tPOeS z#bCi1=M(fkf#13M-@f=a!IG`i0GCXEx{2BgSOp1Xml{M7fwm4}+~?xswh)~%-B4!Z zDC_N?{(E**CG9aP@_LDiboS`NtL2lE2gWXA4eS4!VFf4fau$mvyv}5#nA^i2wxlms zS^!fS8H!Y2!0>N+ zcP_-({q7*dj&&>SZ_oTe?AHTDiYFUM#^DW$vD_E3hMtICR_$&Dm!WhZaOek=$Y)n% z_4OxAJf(J7OyF_QObR>>;-Z5G$8LY{;Q0Txa`F%l=?K3P@Ez_=dKSu zMs#t80H7O`Z8HCM;sJQ^1aHkGl>cy*{vzBxrSSkfJ!{HQ+Uze zSir~^wDdQ-Ft-V5jq-N_=lI=O^{<s#e6F)Oe2OijFO=28apitdK9%8v}Rnl8qS;mBu*L~4_ zas4$RNM1fcky}}4x|IRB1-)p2qs@pT*{_Ktja4$cZ-MJ>x)LATr$5i4NIjS5$RLZf zluSGYiA0 zQQG1chB9o(L0^1BOg%&vXm3c3q9HVFp+<0_H84tdw;I#mYI*)*(`fEEq%w`565(8G z-~l0lYVGBheJX;6aYC0_YT2Vga`3#ZGYOW8Qmh3ykgeOv%SaRV>?x2fM4$#JxY~Zj zJ;{@T%t}L3r6eobOz9MvRGB)hvQ0S%*rjCTJG0t03&BD(TcXk{HI5-Twc&7Jq<|@O zudnwI4OgX*S#;UU2rD&x!~8)^Tdu+lUVAlyXFhg}Vf4I-Y2}S!dsv;5TI=;#E=7^T zF4N0S5TmlnYe%vXY#=3ebzqQGtefgVm-SKT!k=iSKSi3nYHfc-_drF|g(qs$`@Yh* zbdIvx9%T~4NK1%Or@MYp2WN=IH_t|{a^avf!7AHHp5PnOx0HYdiie&@h*{^w$tEqu zL}A_l`-W!hXf-l#m)S+SInhhLhmMx5tXgr|)?mrPezx~cw#7~Yd81DUtkUCi*8~vp zU|YyJ9^O#I({tV}{C2m67y0IDc{B=g?u)RJr@>nHDdQIIM$8A?;*Lw_j!LHc!@|w7>vhT|u5Mq1At5OU{@>_={Se@7 z2wwV|>&QB?M?^>vCi;jCCW*!OwkzzLaSEA4uQ2+XNM~nT#os*$FCFC~j>p=Nb0vuS zi4E0EgXV8-GfCHP-ZShoH9t{ zKfy{_^6ZK+b>DK573I>0f~_jRR#ZWcRn&2h)Us}NLy4);LFAu!cOFLkS|4Gl>=K%W zwU(t%Bz9qyQYdY71)Yc3(|I;GH`NJh9QNQ@8a#ybnr*i?PKBJ*$DRFSRb4LEA_!fj z+q^p|=qDhq11w{rfVlO>xYZc)xl@B^m8@nrU8L+0#1N`427Gxem_(UPXz-& zbqY3aU6T7KxtAp1uALc6$y~%ZV^u!^$kM^2sD(-Kc*-@?7RF-zhqsc2_=dTakzrW$ zK6I5{G^sBR>yX3v$%{)W)FnH)WmDlI4S}aIw@4{<#$Z<4Rz9MCd{VqYjYHq7?LATcO~rk1b4th`0Z$&oh->)` zL>$?1E2!7oMQZV{sqY?yF_;ZLC}>mo-I4-gVwF`N@+7R1P^tm6xVeL!s?lBYEDd)Q zr2sBRNzQBu57S_(ba>XB>wq1ea6vHm3q?2X7pqxTa8jWaEH|J~?JJJ83OF&`sx43D z<2Szy9a%>=YJRe(V?a5{WvAB`BKKC|$CR&TI{m7kQgi zjj%+!TN-Ks%y}AZ`mN!cP37Sdr1Hkc<@rlJ@)R!y8j`owM$XTxCGzv41I$&0g^_aZ z67xu!rB_QQ6pAHlQhB1qR20NVW4SoCr&tB^V9cHUiB>Z>eT_$~Lit!?*B^qET^~jX z`U7)w$xtI_L%bYYqqZ1;MW*j?4(UgWf(uh)-=@4W2W2Gh_CjIC(Z? zbg}wMWp`A4C@3M-#bE|#o6Lu2N8|hoqYh@oA5vnHqsnSnnx)g3uNk8^_yqGfPP5FN zk&MM-_Fsi+3JYBru;$y21NLlwPJs*s&mW@BWXszAf;PSr#A_oz?JjN1KhEI7}AW%vET7=PhZRGkDiDd zSflc{74(2O+G2Sk>7-JHRJY=6YW?%fpCRLP-dbGN{H}SJ?XQC(7lX?7TxQ#TOZ@f2 zGHCv26?Z{+`3CtdUg#8|Bud(;AHYoXLrH!dBg>US~MM^V$t* z=B{02H`ouO+c6G|tk|Muk)D$59(n8z04a&0I$<2;b`lz<+B^UGs9P!}>fWG8eCdt? zb637c%c!m}QnnPopLb)B zqY;XNGAV4Vm!kAu=Jo7zGx{7Mo}4(bJP8G~JU=Ck4=G*Ztu{EW*&-ry@~y%^w?cN& zNTUZzIF0uT5G7IXlH2df4QLT7I5{vRlNET*(gL^_r;N>Ar-RM5E1l>0b~cgB{KtFM zHET$czo;R6Ma%MVoAEi7D!-xqHEbC!;qKh;UUGP;urp@!tpV*5i3AyiLm5>DMvbFK z2w$*TZG3Mn(XFTOSqX@2&Z3=Z>Y5DM`(iw^x$+I zBc1syV4^b;8(Y4J=@amhihlijJVWhj++{h7|N94%T}(*#!&^IpgL>?jf8!z1!y@6@1OdSIcc0p#p)&YhPOI)ZxC~wHObsCs4yqX5elx zh28+1LIeQ6KmRlZakzsvb(}Q9Mu4CeSPYU7jI(;&i)_$fc^%v;#K`oI(}u z%c=s3w=qwf;0z;vpS$sg17&3_k|OsJVz9iz731J59Mam64#~bsskOC20-FxjtjQoE zQe8RPQOk~R=o#2y`Ki!4jyu5LTNKEW$_wbm$sI(oJJ%R~h~KDNm^n_%lS$99r#mc` zlM%2_i)96+hrpYfKsh@cwo3-}73FIBzGo@mn75vyCgnev-foo=;);qR85D~$j**=g z|E9P@RJfAcTc|n^>hOVpuGxT`6f+J7$QG`C{kdXLZPIz%L5cUuRgUtUQv#*rZLkKz z6c*VPJ1t%n3tyJJAaE&I+ijw@rYgO16pzaj9{Lgq2UBoTNjYEiiL&NYZ>39x%nGTr zm9d>t6DCQVnBYiDXVvATu6ya-+4a<|N=~k(sRQYbgpNo zv%Svao(`7Xh=ihfV3_Jq*LBGsl2Ev%ir3mJDh(9BuTImGS#G59EApdm7rm5}f1uKj zY5a0MPm*$*jDkb*66q^P+;yKtV%^g@wy8`6T?nU@8mt?j%MPws+-K>TdmgFu7p#vfmnksy%DIB=NKX(rR}fP=XHU zEhE4Misy32JuLMQ%%hg}$rEep6IDO53{>rDR%q}O9IYq==X_b7hU!&(Y5)5qls}O! zoOWJ?bL33l+XQn}_79$>YOQD$TneHh%gCP~UDtgpwf!6%(FzwehauS<-7yxt9)Bpo zzJ(Znh)yl3?V`0hJ)?uo&QdcIFpOyJxMuIC`EONL`XSxVx*X~i+OJwr5u?5O;@Cj0 zgVk_S-&R`IMEB0pvK&4YcYeQp8@l#iRGK;fIER!<&R!!bv?AMQ9oA;Ua1rOJOY|2Z+=>MO<7#ip`;q0dQ?P-& z!t;xP>}P0$5!%Y4?5+~j)RPr#hi4=`_bt@+C-{3S`dl^ zw9x9~b1@6|hN4~g@5JIKxNnKVn^^sxUfPbxHcS(;`T z+nuv$ulsvK0-B;DVnlz&NaF*B>P4KNikv@~8xV-|f7 z{btyn_XxoQUc^KJRA<5WQ3srWN(w4KkPry@{srz<$5wad3@ZUE3v_+O&8I?^p`f8~ z{xU0GD+@$>eUPD?WeRc%uAkPd$1FI#^#4_13l+?Xx(Eq0m@o$GE{>&Fz~wh&vrawF zP(?U%eD{wG6afY1Y^BD*fnrq_0a;lY>`VChCZ_nTtBY9QsUe7MM&EfN|LX_&W@e^z zY@*`Pi9M0laOq=r1y_9Td$w6iO=xN<^oA9kLy*8NMpFh^Rg}+;yvj-gh_zK|k?kZu zC5jC)7mE>U$&s=f{(bh_nxBFaZ{KWUWZcAEA{OyObbp39Z~S}m4VcdJ&)GTut^mt( z2*p*#h)JiOwe{CpqD>nwRf?}VBUSw$A;2j|DW57>Y{;w|`>?9;^(ip&@(eWS=-0e@v!OheThErSaOtPoP0h6UDol{A-v`Enz^H zkGF96bhOIp6gcUz!2lz&J|;X(+^;#}hi7!DGr@|j6LMF*rndRJ^d~4%4RZAN->jP8 zIUQM^W>g!oXqqy26A>dE#&Wr&u3)5>gA?6+A}$fb+9iQ?kXd$TV4A{+h=P$& zaw|HIC?~4qm2ikys{2KwXdA&8@1idrj?+|Cj6C~1rwA)-XiiO@F?d|TfF>cluRP&i zmH&-U!n{*#Qfw+T1?!IlTZ36eI zUQ&`-T+i4Y?BTgqx{NeoKnx~0Ca1xcLDlFMFo;@eTBsgJPZco>9zumKTdus_iafnl5S+(RDaw^HXngzO()kVSTT*D`DGZ z!gL$U7yd~;1}5(4zIO$jpM9ELGtd;>bc`y#PVbj;tfs$N{n1CpQzv!&cVB*5kf`v`7!^y=Zw3M zQh6>R1eu^xK71<;91<9iidsUkW@Vngv8LDbJB*j41XiRPj}X{_=bIY9?t%D2=H;UF zsgdpcQ-q!HOX;=j_@3FEoH)@xk*dIPD4qQsr z4~&Z4K;;`+6mkuYN8;0&BNjOCJW&D4l!a07CYEzOc6?b0QWUo-70E9;IHAIXZ&r+!Pi zxzm8z_1dRX7Pb^h$iKBXA3oh>m5#AKEjw{@lB~_;I^*#IvNb&(wxmv6{?r8c2yxTzY5IU8p;Ww9bmn4RLjdU;9zaQs0eLXhsiFGpb zs|9)!0i6LkFSh3+HivnyOs6Sqd9KQwve#FmF*YaG*^E_yT$jkW<-(5;u;*GR;ev61 zqpvu|${lppg==ioP^cE1sqYWlUlrLyq1vE!fWW!1*uB7Mu|$za3hSP)-CSU;z2xJ~ zUVI(24bF=7?(R19T?9df{O?5LD#i58)Bl;ozq*-Ozxbly45cF%27~pVKV;`5?Ak&q znOBoMqM;Cjmo@)5S>L}&!T1+M4jF}a$3%NvYGj7rfv21s*(0y3Ak=eefi4lg@La`4 z+Pwl#@#3NNLh0ypoKHr{?bs`>ch<58UTA;-C5-pfjY|1s!uz(q@LrHk)H^NTMm8*< zcJe=DugBs+uIF?Pi&PGsQg;cl_B%Zjnh=JLb=1k-+@R2H-HHxweZqx#uIssdTH95N zC_I{F5ay`RRA3Rd$>G|$VPU_MV0aEt$T8I4=hgd(GG-Bv9Yk^_K0bcJ?-z(4*J} z`rp#chOA3Ce=0Jj$Ju;@ur4IXc7qHHk+OmhDOcpc9boGW4-nF!txWTkSDKQ{-**6V zXk=0LdzruR`}H-!F(YUpS(b}En(4cg^En(cI(F;>imgK52y)ls@bHk;_wty)PaRc3 z0pIrPo7Omv0v zXSB^jg}0?H(*Lsrs=xf2FUe6cVQ?|h^so7V10)~Z_#g7NZR3ArF4Erw%1D8xc*4(F zpU(~wvj6NHM$CcU|F0M~GN_}0E&{?Eeo2MBq9QnRl-PktCd)GKMe_fn9g0oR9B%EG zt{+pblS^1Bp)Qeex|OmDr^_N&|8i?lg|bBoqPH=2(2YAo<#U!TVe{Z6H~!P28RPDx zK{geY8n>47{Qn8#E%WslN=&XEW1YFA&q^Cv*-f$W-UWGC$u0Tn-x_rfVXngD55}H; z`zd7E>-YyDVZlzm+Ko%aFCi--(8oQfWI}>f`qvE6{OU=^+t{CwUB%By*;jw2Lr!&{ zhyIx?k>2!NT%#NsjM`ZU;Gjl@lpH#T=hO;^B2!non1%$E9W3v^&@@CjMn~3OYn^2H z4e%fsE8m1uy?BIpQiFNJKkfHbI#8F7)jH*w6+v(M7mvJW_iX!^;8Q32ca^P+f7k8J zxZDwD4}_p*r&<9SJPH#uBC0o+8A4pn-4xLO(|LvelHPbYgUG;)X+HN->If@3AV(=i z8C6FVqL3PA_awVk?r@4`FPM@goutTxX5Qt5lvEUo+(@Q3QJ{upMa0@`K>OTe=Ah<3 zDRNj(+712Iy`PAjksB}7M!5s&!?Tt|f@A~qSu?OFtL&tQdWM@7U?lny+d}TA_JudqPZ1Fti>_Lo*)XO5i4=EQR^T9bQX^9OX&$$wVh^xcZXPUVt zw*J~@!6XtcchouRdHw?p{9MGYy(m(DSPj=ppy+eg7i;k7_-uy%vmr{qi-qFnf~Aj1 znTq)9Fl{sGjnWLxz;7dV{Pwn)W&86*_o91c9lU^Tl;+NGU~tY3g$sN2l*%4*x{~vsBs3kx?6yf(v^;j|Yxlb;O?Z&?1j5Qu!#A&RRHr~lkyuXum+)bdoo9U6J2t~K|PeS-d^x|5{P2t&0~ zL`qwHQMPGH+4})qd%omhuH`%^L^;1p)nes4+ zz>vQEbk|H_d{y?sJ9YEDr=Z?`E9H%;Ef{sVYo=3Wi??60S#TKTB#J^o3DUKW3~H1m zZ&Y?_mxHmok=fJ|_YP=~m6JN&3yt{Aw zXQbt6@iA<=mU#+N71{)ft0@^fe&4xHlwvRd`f`agWZxuYWL{$Xyn2fFBI=o;Yr^`? zU@@YiX9dMqU(YD<17lb<4ILIKS}t->WaTs?#K@EXkG-!9t0UXC#ez%FAi>=U1a}K= z8~5Pu?!iKE-4NV^2ZunA;O-8=gL`nz+mTLM(&u#dx%a;Nz3=^?_O9BiRuxsNYRx&v zm}3@=*&N2#42vFI;!D#vhPd}P**ez1tuk+2?qSb5_qBWltiMO*=cDJ{A5D+~UTsoR z52{3a3zrASLROc*mVBJH2u?%P&r+oW*TVPq6Bq|}T*1RmVOfSm1g4q(ZjXz-@ij~f z%GXb%m*bOh~*~if-ug6kPzW7>QT!;L<$!hQ*_5 z&am9!*LcvzA?|3&W9o43Qa`7RH1`j_dX~X7d7d}J2F@(cZ?R;|ipu7E5|r=i-6F9m zq696{}<;UNK{ zF@Wlta*As7e*%jY_S>U^yGDzT_B{CnhD<8#WF#V1>#gF+zC`Iz9=<~q5RBicCo!jI_c~CIOOKS z=}ujD-}Q0V!(SJY!c$0*timch$DX*EEqZUDdTb7901>HqTCa6(1WXL0e88gY5oUg8 zg@M_eqH@bHg!EB*K3(@5XE~*pQ3kj6QBh~}P;M4f+q)F*0$d9kt>ZF+}rTO($NE(T0Lq#M5W2!QxM&*%Q549o)+Z z4=|&L5qNZ0A;x?q`0w<1Gh>49qd$evuB~gbY+L$D$@;y+{UdTVw^ZNcNYH5;H|eOn zUhp){K-np;--IuQiN&w58n~g%^6(5{DxieDeA*CF#PHP-^@M`M4(=W{j{W?B*IUjp z8SvUN`ZLO6-Nhh^y&X}i>wuP$%PrB!GTVoa7;QY+ zl{HU+eUA!~B`CG_I;^~y?Gu)Nj#r7eYkBl=QsvxR(Gp(7D&zS zjl%VQ-WD6c0NSmUi@lmbW{nvZyCYh(f4#-D;6qNoQQE9tky~&ikYhL21qGa^Q zu(qN_`MpQ`MRq0odI7iAkAj%I))nCoA?77;{rgwNyKKzhXiuBmDmw z(!_6Q8{?3}jT2@K%GKhQ_5>7M1W|5W`?Sg(tHC%I3V3)yZW7$Nn7ku!)Yv)BS@S?H zfapgA!R83ZErwdSz7v0K*aNZif4CGGdn7Bb!(&IpFaFn`kw0t6vUh&}Xx>FxNcv{U zd36DULu1SnV)2P%zYMXUaHnWtWrsh@(^fli=CFVn3Ij8x$J8tge@9pm@nc{>p$`_$ zJOZ4OH{HJxVEm1|VozqK;7ez=@7|CH{Pc|yhM~u_FIkg^I@?nG2>s_0fc`39Dgl1| z=q=178MlHJag%Hq*L?rm-@dFpKFez6!}p0-y-q{=J#JuvQ37KfW(V~d9x_(4m`F%{ zURAbrwce}0kPXsV%b^M=a(S8hTpaCX8zVe0%$-daeu-+FA>N3aapmJ2Rj4y@+=q1R zzUoZ<`6d|sU*kDU3Nx95R9BUu3Zvi2UP%f0bt z@17y^xIpJC*16g&ebG1U_o62~=KO8d@l6{4*Q^-4ZbdtVYryixlVf9ERw^{Jm)(rB zwy!7-PNN>m%WiqavGMD=uAoG3V8-4p_Qw#po8D{apWMEm+_2AgSnj6)xtRqVW~glv z3}gN|J6wkSRiwi|Ut#MmfaS;&cF+yujC2rClt+G;JF4pO@;~pGB|J)qM@{H~**fo> zjdoy8rfR7C_+wT=#1|YQ6V9QnV{^>C=x9&b^52M+Gt?^c$u|eSraA7LoWgWl+p!2~ z_;^~~q2uO0yHd*2Xl19Grc?8#Xoyi$OL-%qBoOSRQ8A}UJA}G9ScKU$kPw?+DVKAw z2hJs2FA%IY_Q`ewpz9G|r;AWh6X~gPVQh&L_HYrj=+%Mj9b8}W^rIys`5kexCY^?- z(bL|7|K?~vPRm>tX_vcXf-%mowcfx3DqmWhLBp`Yc_g0m<1{JkRrmm-5+eN>+)nWsn3ca#J_j z#x+PC{gIHZbA=9-_zKH<1LJBVU+nPSEP!SyMohp>_tNS3@lZH_wND{n9SuUQ*oefv zWgH0SG4_%BYbKAA$5*s#dDlh1Cwqk?J#cbE2G(5tTsmYIKg$o{U~j zxhny++*lx7eE5ij+*|6Ccs3l0MI5dWN*|2F(`A!DzQ>U-(6W#@sn-<8$gcVW28qZ* zDS{m*(h}#gg*2XftiIKVKs{a>9-do+9@JE zE7CKd=@6PB<~d)W{jf6r4#FI-#q0HYvK^)j(MnrjOqQfw@8U&E&DLL;h)>VtAj*kva8Mm6%O7csG zf^^q_cN_k{hxl+hXa(moYlKk<^1AIf>(qtv!t}qPd+~g~;QxQl)L|!c$*`j7z(`(Q z0pH~|uNXV_Xz=u}u|(h8;MQ$@_1d#^qVABUE_mdb-5u3>}4zIGh`%m@buAJ54$ zS>@tX7sRYgI)3lI`ctk|Nw~d2&e;W=QrOJOJ$jfxeu181cw<)pjCVSJ|Ve4>EQ)o{#;)Jb=hwn`K)E)N_kb5vdLGc^=k zt6Uc^JEdl>%d?pl1sym^I`<1`-oIaLu;k54od3bP$3AugjlwO*WQsy+dr)}fEUGd~ z0Pho+N77jynDsITyHMm@?flldi6r+tBmWbV(q+#r=JJ^Brgh)5co@Lj>ORcZ=_*pS zFR|c8Xqr2|hocZRzlEcoR*fquSrP3MJH>46DILSk=3$MC+Bn`UF7Buws{k^27-#m3yV7$^?l;f zOZJhf^A2*r;#J^~{Mg~}MA`~2$bA>ZwAsLHma1&?j#VB3#qmFZ;qkMPWzC`UVx|oh zlQ~w%$6SQLyS{aQLXb@ElNnW!Q=cY4DP!b6J+$kc^%f@h8rCGX*z%}|LHOmpi5*z< zHtw@BBC>SVtlK<{H3kd1qgNvY`p?CECRDTmV_s>IofECJj)futVfH(0Ppb+g6tH6_ z%P0p7cekr!$jER7Sfg%#eM|Wk8 z0I(x6*BaWBx>N5RdrNN6Ut+o`TCqWFk_R<2S8XFw-&S`$xg8Cxy*%PmHY$;5&2Xnl z>(G68{BAHXm9lodA92sXrNrO4WaOgHy-k?Jc2lbF6bm`2plFIy-_%cu{ua(rIW1H$ zjq|voL_D?jiqUy_mjGy<}*A)DUdqkD~t@spjf_r0&8RYDBV}D zHS0VG*c+rTXK|;j?VcGsjwk3>Iaqylw;NsK$O=^b<;SZYJ2I0jO{mY7;>{PUeaqTx zVcSj+t#OK{a3)M&>u({`X=8K-Oc1pemS78x+w2&*PR-B|O+MJrd^P9ZN2Dw+-oT$= zJKmjyy!q(#CgPPHnQz?;qrWmC@^kp_&6F_Bmo6*CSX6i&wvd!$y^*^wsYkh;zuU7u zPnzSXb*FBiC&2)W2b{S2YZ|Sj{ns?w(t($9N_QhBX%^pSJQgpqomTqB zqXwJGLE5B(DOOE7cp!iYGNYn@vNF^mo^f->`_wu`S}?k3Lkg6b%gIu6M9!LH`?P5U zYdW<3m3QyP$h!X!k8{(?D8JOX(%>^1dmtV~!F5c!CMFeEG0%1*OYv?vGa_=4r99B{(8e*43`w%0jU>dD~tw?|N=VISa?Lo!9ZH-~R zRQ~?^D^=cI8NQ$OVG9M$!>wFpqDoj({uAXV=tKT;&Dc=bGcz8_wOo@0r zkpAK7XwbbDtj`MO*<)x2jsnaZA4lYB+0ETv$kgChJdzrTD7YVzoRN~psUdoeoyf$e zYPjS1(tR*IA;NDCTXRi#(%rJ*F$&%G*;i_C+ZCHc{a2?Z&aS@Wtz(uE$$NaeaE&?t z*N=)cZJjzbb{dGDeQ@oH(aZ@)wM8M1}Zg6J7MONe{9Op%<>mn{b`4DglJOj zvLCxa2GXBF0$Ko&EVPFK!{%B${cP}jybjJ1CD_#(Zw1E-b8Co57n;a(jp-YaeyP^T z88TrIg?_{=e!bRQp^M4+GyOsR-Qd<5m5LNlO8CdK@|Pc~@v#Zf`hqw453wGzl4)}z zk1pFk9QdJF{+D|sNjVw~d<(Epx1Oi&NpsIDZ+hO$rpK#zEt=+549d874G(sy4;pPg z6Q+USpm}}K!vEMn{&rFs{~=v&{%N~)RoPx z=)nlKjfH_&myCdj4w;+Z49hkRy@7+0NQ?B%i0kyAX@2{wEW&BJW9Sm;BtA~r@gr39 zsLBqk{%2rgY)p@;<;zjI)`dH;Urq6G*)I}ow)m)EVR(X)qAv+Htyb~2uqoFOS{-(| zUXF~sn|So_&h)aiH6nr^Bsh`W|6qm*_0@?Oe-f9IUPoXcA^sM@=GdW;Kxatv>4S|k zXoNj+*l8D!0x#}GL#wxFzc2@kcoDFVcJiHMWP!>mcqm=jU)}N@j0Y!+#VTXB;Uct# zFLGP(VzlBM2CI&A{uqw^Vgg+8<&u!-j>36YWCU$Xnmki~I-5Ih9nGMPCcs+C4l{2= zt7+>s2>^}y|M{=-M0rjk8{~SkKT25~7WfQ_^N%;|&Hl>rfGCdQa9;CB>3cPHNC%Xb zGowxytuN8Hilu2`iO|klQoFgiIb{Y(+~4r8J!`UK{my^?9)s8ELP8a-%MSUG=@5!T zGVs+Ot6XN$X5a2pP`F)3DQp0YoyB1m2x?~u-ya^-4zfNcTYym9l0|}8@MC1jRd&-o zi764M-oHeGm&)2)ETHAwE%t^?mN0x<7(R5Ol5WP_=%03nD5ED7WqSilS`4ik2847a z-e^ewKsF@m9a6DbdgFOsw<~qfx!?RM*MdalSbWQbs&JS47A)P!ss5^N21*(TH;bG} zd%?w|o;%=JSHzFkv8|zeXkrfQ3M5kllKEZ{F$`El-D27A=fkxF!5n?hY@XI$YKTnm zJtfa5x+v4Ba;R7b*u@oa?I_nKRo6Te*0b(2KZkhVgStR5kcwNDW z8xIS7e6ZsmA=}UI=kF2FZ}?ETu-ieS0|-a3YM1upB{@vmr=9qWBit~$D&XOMK@yZ? zH}}X%F(Spfe&y}CqO|u_FhR~@mym-z7vv3wr!*=fZW<nC}6N z7_qDnb6&*J?oJ7g10knoaWSAWdkKPlmD2XZcs}-2ueled7RBs!twiU?kTE$hgTbnG z0#9OMXVuMUg<`L0AYW-$fTzb4DBTj2jCy5@k5P~jGPkg&Okxs+V?i2I=Vo@JXh&A6 z4T(hipm;K)UP7)-2Ir!o(JG?}6FOj8!jd)2*^GtJdGU-K*DTnKHwTf$*v5g)_;u9gu*hk-}4M-}) zlI?Kg6ocBJYGp8D@G-n=_vA!Hw<__twdUnc@Y8_w{D;HVpTM?-b64fmU{<=-8EBJF zCC2^KcM2L|WnuwhPu78i!K2;o2#r%vd6UuJr`5$H!Raz!kyT*4icy<86{jVbE7MF2 zuQQroeEcSX^CNIZ;Tz%~mP61^A>n>jVTBd!|w)HJIW{aaY%` zdJaZDDc2EiL6yHsDbmA_#TFxTeAF~e9{$Sacqoq`9t*eiT3lyq%gA*s4U0XeMMTFu zOW9U)%0~x_ZP3+nv%R-!lKlo3;mT%`)|~cudFs;0r|u87KffRVURc#Fc5-6D@U$9x z1!p$xr3i(&0&VoQn#thjja7g+gA^4U?KDvontP0B%Gcy+T=|=AploDuDRsv#AC6WlMwXEi*0UFqimw~xeoN#H{WRDw-7mR z*lx}!DylU+%|1ebw?lR$&>-QXuPK1^0XFyVwt4q94?$efIOgFCBpG$y)$!Exno7SFl^v{wP`n$^ifP%^O3AdWzK}a6ZlLn zpqdYlXFs|bpU{`Ms?|(Eol+w5gK=|im zPNXNoFQ@XU(7^t=P~9MLYCWcQFj9Wf6C%r&_eARNL;cJLd#2*nB7YAu9(sqT(4%4i z?Wo)7!iCLaT;n?5(0q=2{52-TfAkdn3x)-*zdViS6NTAOE!Yry!io6?^H`w80;?8# zY2Q6ihS0|)munxkh!eSKs(c<^y}Vo>;pmf2pR6w#O(i26*k>P#F7& zB3rv7N#HFYJmCa|{?CZ|Jh+60_m6r#gC4xk&(wG_E{&e|-rR)Z&+AG4hR*Qwl9PY2 z$zvYcTA`v$;_8Zn!6Z_UV|ZJ>4EO|=7Ufgm29j-%&TNQ(?EGBPxAA-W$uBtK@qnSu z$EtCuD&Z1ZW-=Ueb1d@N<>5G-D5z7nr;mP_nf%A173|{t^8;lV(k5hfph|rPCnyLQ zsORE}bMD)){wW0g0~G!#dW-=M|C*4-=-;&ZfoT7}Aw+dtgX9EPA<2SOE(a(PWVxt` zX2!i*eJAesK+lh9iLb80o%4Didc+QSSQ7QE3UiqZ7+eZ^%Q7I&Qm9590V587fFT|} z_bJ&z+QO|v9Ba+rU-Z7`a^K~1&Qx<|MGm?@2wC6iYSlV-Iw(K+w-!Aij?#Y5=O%Kg zX_S}7St${45MR6`WtVIazTaj#HvF{rjYTs|%3t|2cjiK-c$h<{g7rKjJ7YPsRkFjt z?62(jxsBo2a6mVm)%R!QF5HI-&|G?f^c4$+N1fIj&sZR1CcxjXeSTBCC1bZQm&0-Z zQXgj5s-6`vno(D~r#BjvJ*8BRmdKuiT&W78kg*n5OKH`|cwkOY04zlUujZAFX4N5_ z{h6eFyWAJ*92Ox|<1=Ym57GHX1johX#7#Q0jElk0$82QcL7AdBpTI(NDB*=}hpk3t zJ9Joe%ywR05F-C;LM#CiLYb1ls9XUI;}m61ewKdDAdWCV~_4DVZo zS!(Y+RM8RT@zKz6OUVtDQhW>JgNK$MAjap2*q}rO75bQcX^{3>mUI?>Kww15@A>^5 z_q-grPVGXv=4`br6UWcz^!>oBv`=U#Q005v^9*luE?d4I$DHt~-TiXv7g`=0zWhd# zn6jXHHP;V4#B;&lOa1Yb)b}3d7JN|bI<4qm%PhDJXbum41RLSGNmvmG#{J_8Wl#ZI zgkhbU6i4|+`-cM2D_j@~#2h7{-?jrG{e(-4KKreHS*!FLQ;op#={|77Gsbs=v(5Q1Y--E~5rc`R| zkveU!B;5;pt7h%yJiZ0tTJ29V^$Z}b^|KU$$?;)UgVS73^UiYjd&TA(J(7;;FjXOu zw}=NbGWacuYf}edAr*?bW>mT#LZ#XhB42BiC&@}*t=-U%1Vj&Te_ZEC6f(`X7jmMh zsjD2qeb46P*(WRl|1MVrlHV0|TDr_Z4M)hlWB?>{$cO(m5e*&s{JC}d1S@+T`ez); z^$+jTZFk+{QIu0gZs#9j2GHYH=Wh(7M;=ow_*oFddnckr`;|7TIGh!4#L@#^*Qq6) z85D6kyUxp?u27~-oYx9oXPiEEdf~=ck(0NGb<%5aB3pas(A<0-exID{4UNZyH++Tm z?n!T5i}Hths7`;{oAXkZveX`B5E^kdJQ+}6!*l7|PXSk%)c0u6FxK0N$H}dL1_r01 z4A&Ci*xRQLN?@<=oS{4$?iCAuMZHqqb_Ho1_b%8L4mSa-+7*k-I{flrvP6o(K4@nl%TsA&qB)u~H6b zl-$Ld2ovu;4Gir~Z#{eK{%G$jl-%_er26&h^0O`m)yo&S(70&ytU6>k5iwujqOUT* zZNPvP^U0oYKQH{eC3O`IZyT4$C{1t!1oVfpU3LB%sV-*Vdrehsz`-NygB8&x2jjC{p4q z7{z&29&;4kk6S7^bk4k%jOWxdXF`X9V4RTKAJlcWA`*lggw<+HyOesRra>=2q44P({a?Aqb{}^ z{l7)a5-P+UN6oUN&jBGfqbb!Fze{c)96y@F_B>0slY*e(7K(X-llHpto96cW=mp>y=T;)1vW2};DZ5$dz&?orX?PjLf$C#W9}m|v)Y z-BWNY!a4Qy=DM8r1!OdS6w@y8lLi<<^9S9W9@lK~6B3$U1fR(G381Zmq{gt4IcHR6 zZ694;ZW?LOB=;BDRFtrW-xgX7+3keCNtjEn=4q#xyFYV3H-AbgL{W(c9eAlpLGC*{ zJw=WyXY)M!BF`UJidRqrHjUcDRADQ|y}CdIRH>R&-idT_Cpn^6rMjIY#k z{bZg6+(jNpJKV-jSSCV@if-NPG>?ref0u9kmPLPJaVZ46_4$@nbF2TaXVK4Bp3-~A z5Sc2@x30lC7u|B5%ZT9@!Sl}-f2s4LhsZmu9$vD_D>LkPAkH|K#+%hieC4GZX_k`| zmFr;l1HZhyj;XwCNRf*^tx_uReKNuqCeO`XMK53JlqfK9S#3m{uknYwY>*{-Ezxgk z2vuRK`xYuEX-`vx3l8Ipt#`UnQ@uJ8ZucEM%rRFRA8}4xKJozDyhvPQ&Ji;4FIpE~ zza*PbAv#2vPorfDW6$+UmqtNHk}Vk~$b#X}zo#06>c$8tS}0{3Km=G&xV)=c?Xbqt zwBh&vcjN=_(r@B3`rimj$l-Z<1_ZoL$OQ$Xg@tW;9aeYY`Lp!xBB37!Wm;Z7jHq0A zkK^0D!@Kv-SB6h8XtEZ#sE-7&rT#g<{2Lg#>LEhDI z=PQq$XjX`K;_8$J^lC9S93AsqTae09Ba$dW9mJ@WL(8cbQgbRg!lI2QFvYQ5xMSvD zJ8*E$9w3f_QrX)cgUYWS4lvGGG_Xj4%CY|Ijlc>haOOSlK1xGa61~rv@PBXjF9$ML ziGGA!OUA9W&g8I{srU_<`-Sxb15{dDSv2R03)XVO6g5(F%UuHj2;0s=Aq4sPd7>W< z`)L3pzmM_yD7NqFwav=R(`C7cnNdUZh@Z%MaXSfvYTmHQPyFhGtp~s!1FDMy^}G-_ z-#oMM*B{x|oLj3A780eg*nz7DY(`ebDm6?wT#Qa*ak6NZ>Tcs$wRlH6%%=T{%HXwf z&QW$r;i&7#5h3-+GD3`4LMw{*%Hcdd@GgM&WM^KiB&Pp-!(K*a-F z(D>I4|GY=}qexwHkK$KAR1>yw)s42&k05n!hi|c@7q$uc3=^(p)5n=cMi$m6^}QfK z|GGH$|BGJoboOAK4Uef=KT=##K7vDR*8VE-%Nh+7{Gco1f5^#ZBRZ#eg zXYQZ;Aw{-)V14I5P(_cu+*`yY9T`+!5;u?iA`g@1z-hdhbB1#PZRaa-^s3{FnOk*i zfDDv+^|II^7cZquJaI_wE5~IAKkk-L;c;I(Zw~$>fR2DUNDryp>zRTh^W?`!K?#ug zi6d4OKZ7#jg&^7f^39Zy98#Kn;Qmtqn|H>Ym6W$)>Fsj_(;vt&5s8Unm8WYi*)RM1 z_^;5XS343y?TxLDr*32}5T_>%L9~P8izGh3=fQrDJ(k%;l;Z~W*yj#$%8PqI{DO@m zR@4(wfp_g$3^*eQqS;;Q+cdG3*?Lu8%zF$4P%3a$8e)1#KRQa*2ie8r%7{mDrsqcF zLSmf?d*n5uCkDcRa_)W38NeDNr_h-n-jD9tI@yT9h3geVcv%72EM{ycG2?l|x8OMU z-{c30lo*?Isnurw`b2U4pF2TOeL(4enur_NlDs{;fwr_@_8E7(k%2p*FP~xrT+YR+ zlcBD@zPKK!;0y+!kAlj*s%}2_4G-4R0x9WN zvaA+6Q#XSrUu9BWPebQ2mN*fbZS&hW0G*BR;TJ)lRrlx-#c$0w*X&zoHTj9zi}IXfxx=?96j zEuY&{1J@Y%B7u#kBZ;)b8Hnt*i3xKs zBtUn{?3shmLUb|-P|go_lzGLp3aMe?%tSG4Nn((LLkRsX?;=+px-YfmUTXInnj$}^ zHU2N@?~998;g%X3BA)}Ho(zp!l0A}_=_=!@YcLupesUp-5!#aQdq~`Joayz7^qA7s z8bj#pPHxX|X>+v!%wt(nEa+@W?@pi!c>9a2*!OBB64#p~8jYcgRxu3{`)tj%jhd+VST-QJYZK`iJmxRb=k&b;*t_G+1a7XJMbfR;=pab4iYh_9qf{ zBWe(;DKTx_6?YBuIts1IkR(faS?E5_*(AN&mXLE{0SUV&yUXN#^C5nl%GKO72b-s# zO-c=;0H37ITbO*$Pqnyt?5ihr8uA4_HM5Pv_d^jOG8r%;Oh zwmd&HC~as9jv!e46wJ=|m3>zjzCdKK5hm)8QeMX7Zn5pkmKIPAueWGFAaZ`k1VvJJ ze*>HA86mWN$cy(KTT0BWY&6Jy?wqrlsknx{%fDVyQEyK!&@oESdA?oC8up54aS>6D0##dWspHhx z)E%y~0(j1yt^&_3C-L=U8;+a9GflUyji8FTL4F?I_yxPm<=vX&$RQM?+7xeB5Bi4H zE&EWmj0~+g<&W7Jsq3aV>}xazXP%g|x=JmQde{uMln-;$%9Kgf}tQ|N~_K5&SNR3`Efq-KSEllMWjfT9UZ!g5zuxSxQagC0esPVt3)7F>E* zR`%q0!U!uK=KVJbp&sgnv6LYY?**G7PE_p9uL?~b)8+`gKa`QIwz(LMD_z~NdDn=U z;ⓈgtGZO%=VNq>S%XVuzID8t%r?mB`#=TZuw1kzyyyB1OJe(#fT(>v^u4gP+lA=q8CjG!0x$cZPw;9(QXSC~b_Z)KM(XDjI9#o|;X&V$R;e z&V9nK`7T##KpmomcHrVcR%K-KgrfXo(n2mwrU*D{>6=v+v(z)y;Q_f?s+x zHx6{dhs~#K4=6&7u9(~VzH7SZi6<05|2^o$>>9{)fa{>s(lfL5MavC|1uA1KcF`l1 zH)m_Gg@!Jco%Z!8C&ein-SBhl;}oq<;Rb%WNX@ z%1>iQkH~}#46`eZ+E#4IDV{~eeVPS>1&06!=Lgjex!HhlhHlglCet`ILyWeV$YB;O zRf+1s`tRG6t~KsZ1uU5XRdpw9y;j<=$baEVy6`MJu%X}pwid{{jP)_Efn-7HJV3KI z?J(3$5mbwp#-o*fP0m&HKWbu;N!S21LqEiVu4RIN_Y7KgOoCE=kH2Li1>9g7q6d3TCTS zA93PT(ZOE=?4pm5j^Z%V@__9*Zz{ipiiM zTvyGW#*p2~1Ck5^UK(`V*(M}7r^oIYlY7)fdb3OEavy32-`NRH@*!20J(PEf^tarF z!N50In&SrVfKj_(`~N@w|BLWnI}(H$;F(ISNl9?u$UHg;6)m=-q2baPup@!IlpDY?pcvoG`9};_#(GSc*CCG ztW;gy#LKwR$SCzR=@c06GHEfXqQ0p9?>8sTcQmeL&*PZbweHdX3W zR197XxcByP@38LB{Za$XbY0(ewsZxhf;2|3vmCq$rL^EApp5YmM!EgWay5xu2c`R|Ad|M zZK{Jmz$16vVey1J^0H@9&dz9FnV8>P+X0d^MiFQ1-zrjoCjCk_6?8t4F}RWG%J;tqSuZ)UdgC=yD@DV zsZ+1&$1s7)h*|$(=w8WFJ~fp}4ELmk61Pd_p3}=n+0Q%X?yjwcv}{L6?O!qRaz1-% zT9g;=PBT@=9+=v%B$KB+w)U1a%20h^Qq)&rH;vLw$ZD+$R9xF~^DXxlKg3l1+S#f% z&>p|QbQYe0aP}?fTe-yh)kGHgt=#1i(W?P0AIQfgQ;GHfKr;Kiky$H+MHYHrL7_g_ zAyeide=%XHQ?riegRzT2x1Yc|YX30iZZYT}H`ZkV%89Y|kqVX?qr3LWj?lpSs{tpc zVxf42ns15ma~Jeja;mgRZZDJ9fbJYL)(nI*Jfv@hbxCXI%3GCt*>W2qLVR}99+>RG zg%hW1r6?8E#kL>he7}01z`zOw^sLaG=u1hxVlr&m>Qm3AqMOD#XFsw} z^U7XR|7a8sjRx8{Ljwc(pkNWS=N^w0XrJowgK~LnO`Rv#D8a8Ve=<}!;Ht>`JDV{5$k+!`_sYs-U6ceU-LTG!gN9{ z71cO>a#&dxmnA)vu4a{Y3Q*3-@j+K&Nua`&4*Ixgh?bLU01mauJZc;9L>>$E*)w<8 zm&fm$H7nI;qD|PEK^+~RfP@pTM>arJ zCmO=8&F21bI&9(D3kk#4gA>bmo z;bVLPo8e&?nnlMI=BopF^$wK5*A$kQt@BBxP>~tln*}Ind=(gJF#vDG(?cc6bi{ks z6T^W8VrA2VqpY>EQ>QX@MVOve*qrK;Wc^pLYA{3nDLF+f6l(-o)781tYiyfHG{jwS zTicOX+Os0$xbJC%tF{g-4s$9}{aZ>~V|txYptBfW@qSROwQ$oTy}#H$-nrv3$omOw zPM&|%$*CJiEX|RwZZFJorRb+RV_R z+kvze9R{_+V-H-4gdE(uC7MjXLi4Pe6T23ZKs>==PO9>Fc#v8Zd^F2q0L#(d@y^mT zNpCKvL<-uJ2-R?}B|LSEAx;IcLr`sfac^*rZj+O7LSFzz77-UmsSsVKj71<3`@^tO zjBal}Gl@gTa}5o0^BFPgBHWy(iPti4;t7u!Q}|ef?me~Z?c=oFC{G#9*ElUhGS5^i zfyrx<5gW_2Z6)4}q8MQF;q1v+jkOd-OH&~Jv6-a!Lw;KO721ulYjHxNEX7^54(QgyxOx|vkF%VR+(QePZdT|ON z>o(|FX=+YDK8~g*pQ*Q2<;l-h{Q#^Mg^;ROiYQ`{kZ-feJGyq=Q7i-gKt6HK{O_5R|K+VywL&M7UN5|*jMnW_Ve@ysd(>_oT)bXYThsc)=O-ii z1cq^PchcEVed4phaPrk)hyxi6=AR7)7F-01b?s*UL%Go=VLhurKZpAC-~*C{$r)D| zyu=QJrneqUkCn%tG-6sz;I(!Ff?4=teCJ=gwKW!`PM@c|{sgv{Pq@YM39MeuyJT`d z?pSgD#3SspO}NZewQDdA5;T*~LMw4LK#j3Xv&q!@gWY!0OYxLUItDrhrX#&k$XK+X zPzCuS=?T(ptst8IhuriMNKBg+!%@rxN1+% zKOW%<-wVn0QT1t#A6g5Hrx|nws=gAqQTLFSERH8g!S6?N8nAfyZh(bW4W}@FA>EX) z9Xpz+VA^tP;bx^eH^4?iZ;WV(3`?eC&TV=*N_s{M^ zPQioyr_27pxIJ0O-Z@@;pi0dDp5+vav}i+wb5JB4OhR<})yCHSxX@F@p-jnU75tpO zc=uY(dc^@bmz3QJSJ^A^^C+LdR4Ys#wxR_gs1rXHv_6NcaFgA>*h%#fa`;9LT;fAO z8kLt3&`i=3fy8~Gwvm%SNV23~VvuaGTj&*&ib^0cb(#l?Al+%tN24~B;LVZr6W~)vzxq#KaLhf)9nzUFQk~JEZUF-g6kl-;>_&YFKl*f_JbNI+pVpwU*m>pniw=32cgA-1jb)|2pS< zd)|6Wj+J*&?9EV0>d75?k)tlZ!eY}6wxJ>Y?c9MEn3PuVW;hZotFtl4PouFoyo`eBrA4`F{xiX!r$#4miuR)nsiE zgS>L{NdY*Sc$ZsZ3{Q?=B}uUz@o1i;s^ILb@q|JjrEWN7N=Qp9oKCOSIlL!!>9#eU zBPk~D>C3B3aLy6_r+=tMDUY&)dx46X%T1HIWj=OTiYfDsM^Zx4X(mO;3@z>C?k7WF zu#PcB+uIJyOT1l`+aaf>yWMs$W{woKjZ4ZhObl_0zT(kCmj4@@t9v?|l!^9e)JfiZ z1||e-%X3!`akx~oyd^jWE^bl}^dJm?Ow%XA)l@wsMk!iV`W;TMvRo!ij;$iHwXR({ zOxz$>)Y%1=TT<|zAz#&WU9$BFG|e-Rxr~??Lr`Hg|4lB@8k&bA;S+yS((3$rUS>(6T?ysVLVm3^b=f!b ztOIOSQh7uPO->?#ngo#Ix7gFWU;qcG!tvo|k+nP>Pb(O;9n{&5^FVJ5a*MK z^fQ`cV@uGRuU}L59uKectxf^U%U>E0xa+0ejH?aXT{B@TacD=M(`-p?cnuDTN||Yd zWzv=#UzJPaTB^XDcJl(hrJGleXUwpkb(_{pxag6!JsH!=rejuF6t59E4P>gkq}wF7 z14{*x;WBIPJ|@8)n;N}&&e9UlR9?<TVCubd=Ig$wyvU1`F)1Ybcv%+b ze-3S}0%+Y<`Pf}+=9VJ9g`^Vf^Q>TG2L(&Hw^6MGzN+Ej^Z9#O8M>Uzo-rv`!3rpp z)ZOUx*NSr_M!kc>7y{5{fC=j>;hbXQv}l&_RNP(wGBMvU`50$dSN7<;j78exPz^cn zLWUu(f6x8=f%?%D{_-6|!Zba!omO}Dg^bT>$M=LSiC`+e1O-uIsP zoOABIpZoh~_F`tutYOxgnQuJLci6NP5X_?!=r$K$9SxDvp|H63uZMmH92}b!4Z7Q( zFOPAJf&;6|saa)Fhy%5q_a77sn)>>1Cb+zhVI>_M6>Df0nEjaFO7#qozJ#0vk2=FA zuzkSV$O!zi1SzUyD`W8T@N7#|HQI&^%dxzWAT~K<5tK1d!xQeXzo;qDO^IjvYL6?e zdkL&DU1dJ}rKNneon0Q;BBwJTw?OMYJt8)Rma=)`bvQ908p*U*XuhWCeT6*cifGBi zBgY{g@>^v03LC^z^Kh5K4_pe677I8YAvwY8bWbks$f#5|y0nSUO`G{lo8zr_uHBN1 zW>=P_}>0CDu#;nJ+@k3)B6f2xUfh+_fH@}W=SS16yc%cQ9L?#% z&@>27ykC(Q7CtsvI=jWEJjDNzjD(vVs_D!jnO-#s7woQr#q;DOw zIL9Dn_;)^;f`@B@o(W)LgqEedDO11J+mbKe0shze9~|!#*AI3yGNex7i&&CUp5;Mp zC7PnGEl(~1Y98v-cG9{&~7&xE!`Xu5JZb7%UzZI6U zyg;ZPY)Y=A$#T2G^Le8VgV0OY3vGAx$Vl*cA=)#Ojv+%~@u>zUMr&6NT?4g@)+`zm z3Lz$zT04#ivZA=eT(GsuA=-fXtcKNi(jdL*i%~Sx?|^rp@EYhk+~RqzJGSxF4=xXT zg*`zT&vdg+w?DK3y9#YSZW&ffi6%<+x}_83UnmlAWsoP0){QdYUUGewhEP3A-vx~m z5^R9OCF;9hv$WH*cg;`|z6 zzqop~;S!6pXM1OY!!e6e9lChO$zL7L=6cmsh{0qglD3dABRo4|;*8augGp8O3VZ zMjDk5v)V)4)FlbxaNPDbUa*Z5PdAcES?g3>-M)N>3%B$u7$3>3}* z`j>cJM+qqo8SoY7hEXFfkK$8q7FF~E&56yHYK4x!Cn^Kq&$C~)xAgxMm;81!_)(dk z%p>Q2_BI>LPAf4+MN&wdqNg`D$?xI;Q5{s^vX%1LX*c=*-|ok7p=vI!?triJ{c@4laUaVU1uGJ^nm=R+$jEL3Plkgzk%OO718V0G5`Uz8~svZo7CR$j41Jd;=Y<{U!P}b(@&y zAKgqB92;&Q@YPX!dt+J7DV} zjrZHWS7O#6=Fbp1tU0-dj3tbh$pkvZ`fx#I=e(cd%Zubtx4r^L>wtb|Z?4J$rhst# zaI5OPOm@A3;f<*!C%k~C6ZSYWRXg=UwzQouz%Us09^isE)5XD@e8YHtpaLl zIbKQI&_JI7^}$l<&E@89g7?82TF$0sBopSacjT{-pRYYt=#gm?S*-usPl#%5@{PiIA z`)p<6Ur@bZOar5bsRB2B(U+Z5n>gURy3D_`S>aM*a(GU*UZZUMWbfpx!aD}XD$}Shomj?vLlvPR=5dn!k?8{(Allov`M3XJ}F=n!@FufBak6v8mz_CKZqL<W=aLcEZx7{*ihBBQ%b2g@bFVRk^)i_6e3j%hfgUX?Cu#%+(e% z@dj3F{1Fjk^Y(=_=O_29ROrGRYx-dz?)C=2IkeMpt(|$Uc_^J(x&5@c;BHi1m^C(F zF394m1|X9@F+Zl|?dLwkhJ0Q$Wo?(%Z{$2nMn^Vx69(FH)iG^8uLKj>{xTcLMH~Dc zt#C_BI_c`x+LuXPqL>N5ig(lS2H7`IXDs;;1&GYu9^3o?#Z)@TMQOvE({D8j*?Cwv}XZS zTv6q9I}DdTrGt>Bd8Oy#sgyl5T&v6nzSLDKZ9MO6S}?&@H%n#1a4aua-VGQCDg81nvi*|g{`ezn%qiDGq2Z&(yRdYfdjfSPmQZ0?_E zp9NC32_9X3!?wTl{VUJECuwZa1BwxsQ1J$YYGV5x2cmOIimhwPNWeV$&?2`gM>k)4 zrhVYkR8Ma@K64SCwL1qml4a=DY5U;Ex)y{R;|ulJqt@JMuZrXYL&H+SRf-a%Buh}5g8P?^LNOBhxGeR za}bQkZhLp)G|5(hZ%8C$GDj_W{6GE&mi$ObI`X?!5!lv%0HO2t>2TED`q4{SQ~M7Ta#AZnsFQzQ3uw^1`s8(H{oDyLhxYT3##H9n-I0 z1fBOCWdzz=O9$buY{vf|fAW)k+1aq>J6KG0RX+>g@Bg{1;;WWzhp6jF?>>avmVc^V zDc=F~j#ZO9Sh^E#5eWqGoSl}TiAv1~8v~2R$qh-5fz%s^51r56Uma1VYp_Qf1iysI z4I`N-?01DdmodpS$Yl8p{-!P!hmdh!9OIKtlZ}nvH4rJb`(#=NM_iwvOjCxhDBYNL z*HQcJd`(r=l6ssiHEqOODHPK|aT18^RYB4XD%AtiIfOpTWu&A+ZY^ky9yE#y+)!u-*j9srEnWBi+k^fsK;wj#BHk2f@-j`@)iu&&oNgP&T+JIfm&GVM? zC#S3iHa}exI=p(vaYTRNr-5mwOWBFWi58tFV=42@Vv%d<)7K!)v)Ss#-Qi$AITOT#54Yaof(2O`c_Rkz8zy}IYx-Q$!!Io(_8k`KGxT$-T^ z6DlBeXK^(<+>k6M5F+e1@L9Ym8|3>`9N)#j-L1;qoHQ z0*Ie(N<=JKjQMGZd$3DhjW#p|abF}w_l*DIx{c`OaBciMpr@f%7)RCWeXxgyuDW1R z4%cJEsuS*BJ*#aimkj|58}$tlAUt4|c;3Y3-jo3_o)j@pfM4g$ zCASCV!^EmD;tj<@zx6#TF558jueI{>oe&7~B?aYsE9R&sWfRkaKQ8=X`2ITJ`6Ogr zogZ)C=1r4d;(Y2a)X{BFFzi${jf zUF*Ed)&sv6rxQFq@fSLx6~i&cUw{lY?E)yBDR@K=o`}P(>cdQ{#_l=KVgajFBL=JYth=@aj0xq@77FFY+txf4H8q$A*Tke&6>XX5 z<+BWrm`J5JX541d;M3*H=Y6@__w_F_HaQkdVxB(#4iLH5!^LvVxu4pC@=^y-;~K7F z|5QL{I*&bL$WovmC`I^7uOn9EbHImtB1+DyTFexN{*GtuclD0gUr0u{Phu?HY6S|$8Fc_zz!;$-l8vV}L*I+>teL~9D;KHl5lk|{pDR7@Tc}Ah|sB&lE z$NaXQYHD$W@nRdjS3v0`C(23TZ9go|pJI}c^moA5(xF?rU!KnalC9$2;Z!=paCp3~ z1$0Eea{*09dA7AF-McbF>7DO@QEj+}0mQZs01cT{kuka-F5B4ezS*u>NC8&Og`vLL zb>!+o)@FJ%oO_l6?nZgUXVc0ho919Qez=Q2aU0!&-T4w2d8QSamnS%RrKLPJsOf3OELCAHal{;rD>ixb<8T54IO}Z(Jos^4 z3GZ$G{RNi9!Qv8XOK@KiO#Tt-cuAnZ{jxB(b~JJbZ^yN|a%Tw_++8FRurp6IH12lT z0{F+G70g#^E75W{%L#+;my;T77r)PoK>O$K2bk2=gzOVF8 z6FH7zeYlMSFGV!8`mxU|k;Zrmvnbs}4-2ts|KjDzck889849i60WUdwt%WCV#nd!; z7CW?8hF7f+x(s}8^>}>?kUp~#5Bq6&^4l*Vjf8rgu7Mw-iI0;Zm0Hy4VhMb7pJwg; zaOp}wxhnJl`8$A3MBQ#0$jA4oYzSZ$QZLhLVhv8VCN^fA{Qhm(q$z90* zSZUzq#Bvyf%*qm7dDUAu!|W)VJ+6LfeBKP)MK0vdko_LCu-v5n6%u?SV@wvLcncMqhGqQ7E-(<}7-&)s;TECBVH0xfNw> z4>>nAB^nrpx9>q2!8@01Xp*)nW(u3Z+1*a`jE8_*|Kg!@8_l(6f0b;#wnl}I&dCTYSU`2VMA-4$t%$p|)V zhb83JR=iMNr8HwSGU{ENw9eXZZx{EUeUYLq5bVozzg-Ooc|A_5TlJ{zMcvJ&mk}t` zaZmP+K^FP+e8;U!VM5*bPVJzUi(x$QJ@V}xYv9|+;-ff=B8EqFaq3-5Lk0mfE%dfw zZ2KfS)HAM4cBpx*-vJpHW(-yjzsN~z^;ODi63CUKoEwjPNVl;d2wQ=l(`O5OhM2K( zT4Fu%?z-BWTUZj_74Ow=^1z0IP2P(umLFIR$eZ)-L6R-YM_o~+gu!NSbq7haa|#CW9BYHGzB1MOU29=~zCe+X_@p4VNR?}Cb;|xzlS95z_zpOTSv;Es zrs{^u5u(s^O>Fjnxc5mB*v|2Xp?W2?r<`r zKI(||;3di;C35|yOVUh7)RPK}XOmme<%e=TWiae?RNynZ`?GzH3Y@9%xDM&DkQW!z zoku`ezs|NHJAS0V)5ZO-0`UhEmwz6@F0~AJzlW6%7YwIN*tI zkI=}*qB6HZa{`Tc_d&$!Hf?;Tkg7ow?BiY^{;)Nvhm&@1Po%5bdB|ui*79Fo3%k`8 z<%sIw_Cq7o`B_GPuc&NFqOd0f0dv2EpA<6_Ua+i9)Vt+0`Wh+PAm{j*N8!Yyy8mi+ zo#j+-glimYR7OV1(ik8#d)*TJa7}DK$CFGbr@m6>Ni44xl1!AonvF$i2j~4%l8EqOo{G*ch9GLS zp`Nqp9Sp2hJ*oWJjjEtq<0pRyI5?j3T)uI&MRSdxdam%JeJvCP*MPD?BbRnKxInu@ z9EcS9&O5JjCD2ytM2C^3q|k#6FHRHG7$4GG2wjkuSO-nm(PukCcWR?Y_&_eYJ(j7^ z`r@@JC6KYhvyW4Yk>P#xpKFuX?QH z*me^gVPh55SkR~O%{$81O+IGT#LiKNi;%HtZUNb=jxdrmNVc(f`tdy-o$CUT z0~joNoPdJ>U!8`!FUc+voK;|*6&~!X&*!h!ar6e`SK~C?d*Z)8Sr50bepZGURS4er z1<-GPcbC4j{zpf|fLJT~)=`-9If6(FDI_dAFY$$dIQOan_LGDsziy5ryy$VceKl3c z|7r7y=F-%>?00}$X;Hj?eW>W_c!M5lG)lXccJKH)%^mTuo8WVZ2>vuF&z%HSDN=LPM4y<&Kh}_<_g; z-@g{>`i_9YO#Bt zQH1=*^b{Y#9Arb3p{e{Nu{jiNO_PhpXH`$)FM&M#HBB%prCLc{XRg_a58lF|sb3=- z#}?1DAE)Ne{8Vc5Dc*6&q-2k;#84zb;hh3|-QNjT@7^%u4EQNQiIVt`39mm_f=N3IBkn-8ai!?(LT4oT90Z z-vL44mH$FM*KYhf`D#H_Stz6NKb%;iL2o^OpIDr>+9wYzA@sk~CNx4E0t$ZPO*97z zRN&0&pDAp!o(tW`O&S(Ki}k!yl=Gao4EZwsV`7Ki7VJfr%_PNc z6vEm~AJBOCkDBpWEv29GMg1PY6{)fs;xkeW2)28*s2Wf3?KM zL^y@4vzGZZF)0w$L4Lk9hwxOLK+b_OoSb*MD2^Pao7&f2=J-?wr7#q@wJ^{VhDWe3 z7mgBMR^>d)r|qOPeCNjr_EMiv!Ws%r+&+o4rs}RNgofSAnGsYv3HT03@i2e%9WYzZ zK6s^Yjb?C~_t$A6^JALuhtC&SKqUqtUAAW%LS5G;8%+V4T*F^C4qOH?WDgROhI}E! z_4=FSS1pWgEC-YAd${UcXVmcp9Dw?|TXHEqZ%4(J`7_I`~d zMDA$+I{??boAry^yS70kf>e6;stJAHq~*${RH!VFV=~m1Y^{YRAw)Pxr zw>UNfvBV>k2nt5C59qD<)DQ-#syx=fSLEBY6sh=-r*Lzf3^NhlH^h)ntlJ!~@~Y=2 zdtDokveYX0;^LWj^!~DI5zWxA_ZitIW^nIJQJ{Y%`3+Mcl6auwN1qzFay_bi4udUs z7o2lV!MPYkGM7gulaWL_p)uzL)mmv^W5c6uv@I}B zjDC^bac{h4=0Km7odrdb&HM*WRPI`Y$b! z1=6+wVDf$El%@keJ|uH-fA-nM?fsXEAZbQhtoMnm)}Gs~Ai14<#?^FJ`N{YiYxOQZ z=M{3^+G9?Ij;<#b#CE;XNXH8=L+&}eE}979^7j+`$Z8d=j~Pztg$p{0p;ludo$$2Q z_zqCEwv#8je!9^a>}?mcbP|v*s->X&+wFs`1)3g`oa^_%mnUeiV(^y)?p%J&(eB!_ zY^+p26e~>^!A*+4PRqgc0;CG`FuwZyG8Q2?5%W(w$52`IA-`80y_9mOu?^Bk92jpVU11+ zO6T4rQs2fELr@+eC!sh+l?IH4V4Q-zUa``qjo&DH@W45iaj%`~zG?{Ua_td5Qylx! z2q&H>oxD0QXNuvvt^0@Dlx}E!UMw3;C|m>$Wi(!wRqg_Y&p#X#nB9Kv_4UrF0kwI; zpm%ZSrA^^|R`RsqXm_@D9`De>@i%6pRj_!%XGY*5Yhm4aSc9gjoMva%d8jOJq4Q+% zR{~~7PW^o`1Bnq`x^UCPPnqvkod>8 z3;cO%xaQuZ*QeBHn4?fuB)M+y#Y|PY8{9%3mn4xRDsaXbkuDx?>P;2mTv&ax^3Kpl zOJ+!Nkm zrrNunWmn(f#8Kk?-cGrOBthjFxMT?Holh>rWmDIX)d1wCp+1O|agQ^>yJ1m2e#SEl zk;W0?O58*0Z+}n(n*d8L-m=*p=^oV7U5z%uG}b?-2z}+Prp{bw=GLeCjb3O-rx6O& z4_C8=gDF0>ssG0FHRMm5dAQGh#o!E=j0{`2yemqN9{l5NMtaLqM{J9%?F&sq1rbLQ zDs3$gV@Z6iSPKC|woUaI2hDGtv&fykh9+XwVA=o_-8_tUz*zHaHNk*?Q1$zZ>-^%eSAL>IA&k+UoSwVGA0*h^3yAz zlPh@SBCK5EF~FwqDJL7{p}U!RFamGuf#nqS+-SH^4164_YLmJ<03bMOz7iSx%~x;d<(ACzjwlVe@vajR)-?t9|C2!ZZNthtd!lL&I5s!QFTVixPx!X*#jMZzcK1=cZ=pXQzgaVzce~763i1DMj z-v{DVOSAw)Cdpq{<%|_XjZJM7sd2PI_Th@E-j<=}qp(szy)ap)R68@~7hI25c9Bq2 zPMQn{!u1*U`Nyx^KE}z}{1>H7f}wXhg)H$ywZbcjBK`z&84;Y4c};F5RxOg)T*_w8 zVi&X7j^5D@T?WEgkid|kjHpIrKr7b?DAah|l)hw9KlIK-o@M*lu7~)5lYWu4aXR1OKxvQ&dvp1*b^J$D zimnFnDJU~nS^goR{&3gOTxpTF4oyOscXEV5fp~26a8;~$NH7*ExKYM>Iil~kQWl}> zOQKzt_)GfKG1c%f)wv14^H`m4rYF0*l!QLm$1AX|PSYJIB`l<$%& z*_LGV)|zVnkt4}L2;-(`0tOw^Rk6`xuNe3C!XI~$Z#BJ09YnNqf3*K%D_;P9+W7+8Zo(CT&g?7$Yv^q1e=9nP^7-FJ^Z2R0dsW>(t^&s_X7?2qF?`BENvpTM%W!a&J!a2q%)fc~WjEVly zDsb0nA8<)B@z{a{mrEyo{4sCJtFBu*OUq9KuDU9zZHid3)|Q3Extkc3lxI;{*_75{ z#Z+88{eGiTK{F9oGQ)$0>iQn{Gw%Oh3w)O59J~9H*k4R?S8X;BjAxVh9gzD0!?Aw% zTbG@G8FtbvG6RopSD7EwdrLW1XO08Tk|H6YzWW3nz0ZYeco+TbN7K$%*}L5o8^1qc zXq$hVd2*BsDIjbzQyoX#+jp4MHBqWKhu^k1> zxELos4|izN0vvC-BlF%Nk|8RS>US>W7>4GMj~sQ&03-1efLeg4r{LhM5}h3$ww-hj zfjn41E{x#wI$@aZSra@)3EWi^1CK6Q@^QaLbyVMjHkd$RV|!lA1LNbDy26&}X*-4! zCb!AK$}X3H0Yu1m%HIJW zA;M}mP;&cga@5c^Q1p%*S>|L}b)P;@XS3QOqw}2!&@*|-@ePNyDkY1R7jD4EumD(K z)*zb4z=^*LG(y`x|2ex=(SBM36k<%6G}n?=VsYroL)mi^N)D?mg3X&-q;`I|GJprJ zU4p{|z5~vt6rBYaan?!NYkA}fb0?HM6lRAFS(5u=`KG5OK>&riB+f62*0Ns~A%}PD zST`Bp0SY?_g_P^FqnNYRvNlf#iw!WD?fx_*KtmQ`HOx;w;enDy5~DkEcwaEAA9hSV zaZVw;X*qGT+n{GGDB;jS?5uIC{nJoN&cDiez1sbiFDi9jAiu~JkIVcM7k9t@#uxEK zKU(`M3n$NmigInfFxJ+zzYgdQ^BPdq02utx!3ciL9;0AO#ov7Cj#fT4rXa@H68{s$uf5S!v}p8 z=FO6MTZ6_6f}F0=%Csz-v~R5wB;)sGIaLz=G1})gl)NNM1?Iw3JPyaI&u&pZ=}Vu3 zg<0<|+W2_wmzMfe!wzejo6e`EnrE*rraPE)*es?LU}`USC9@|j;Vle2JLWid;I_K%^S?` z@W;ENKcS!P@71Xh@~|5$R`u+6@=_!j<>Kk=7@*qi)yJ) z*i~aFC5|ckTK2kje>zr$sAVGZpbr$)DMEq`Mdfpye7uEtb)+>h5{(AA{NDr%_~{Y) z4lt?v`goB0*UNNsT5veSPv7uJymk~%|pEid%aBo!*(K(TIE$|^gHfRJ_gRXIG9pG)&D=RBU&{*g|pl!4m$)I~u+}%x4 z5f^~?Qbn)7{y}2+V|e&CFW!uX-{0{J{J1ti1n(Mu)0=2dK5GD9>&z+76$*?+_ z8x5a)BBEjt0YynTr1)^J)Y{t7o$+-eO8nD@Zo#pdqk?@A^X;4s)i3iuZ4Tk)pJZo7 zKCs1P|8OW58*N5HxRH~7RWhWQw(k|5c90*C$1{D-IY1a_ZCl6&WU%Pyc0{v}}A2fbI zb9VNx-W6TjFSMzo=`roHc&xoYR;L?%PD9N2(qNz1beKsrT;qM^ScN33-^1e`wmU>y7ffJO22P!QilSW_#0=}jCc zpUYVinw}Qxc4y|!eLS`}-*OqXH2z-x!hU^Cpvhqq$w)bOda6s=&-FWCL)u?8cAgz} zrQh*+*OC`hLf4ncEg&N;9&m{-+$1PqpY*crueYkG$5CUe(;8PN8O;SMOCdqFlePO! z4hYforP1`{ywD8Eg>L8IoDd2O2}ucIdm{W@9YZ8z{j3By*Mk%PPyHDgc{1Og5UxMv z(V9s9iR9b%;lbif_mLHU>PHF@IT|XLDl(QSp!x9AYItvWv!9yE-7{%eV<^DWB>J-f+Lbrtb` zAp}?%>FhC>K_|wHS7QncomaYSZz>6P6WSznw!Q~4g9s;mBTPXgncx_N^R)KC5wBeh z&|VxT_$1A&MpIa8DR->g%=V~ve6hhhVnsXxZ{0-p(DlE+-+~@2?QYF8+Nri!%$`Ee zc1=?7?YytCCqo$ewvk6UGvotr?aVH;^d^I>dqf0DYFbewV{LFkr+k5P4|$~{Ooo>+ zQ*L1rg&xH5ZE1V0ZSaE&VjkHw0%N`Q3>Up#^nS*bwj?JVDH6pHPTITJIb5l2EO&9$2pSyhKrv-~L{MRnJEV7{&^xbBT>{pV zGz7N}#Cs+fH-wvAc)XK|bWKGP&+Mzbe_sz{TZ809WfAdq)nwbNp-}yb82ri9qwwvB zl>~)45|?P%&q?H5wezeHGDflnRuV=FS7yAV&gmXJk7mfyZSvw!U38AF-Xr@VQTUWG zLj%UH(r8bBZEQ!oD!DLS zd0Ucp*Dsj*;W5Hutx|E%Wr0wa4A_i5yXXFMeoM;psw8{~+(-w`Jm%MKr2_ zd?u3&D>+|b);H>a=kG?Lx53D#W-QWs{lt#1kuC3e6vgn(GGw+=@k?XCheh0ags$`7q~J)1`NpKyhFk@n^%EHqRLh?osE)u7@WY=lr&SA#E@ z$=+zul&w{#*Xdw@LMVCup{uEuTTIB`12?bY*0e2)ZM9`fLB5e7czAVt{L=>qL^aN< z>V^r4o3%FFwdRHK>{_*E`$Oxj`5})^NVPjJ$m=oukQlBtO#)>E<^gJ23%-*>$8sO; zz|?FFPwu)1=e`^y`g;1ddAr>3X!{e>imz-V4Q?PP(SQ@X?`HsR;@ztBo#%F3kwY}>3|_X=&Thh-5+;j< z)9jEhO=ZD@g}iESUPJCfn4q4RYrg5jY~(2NZA}Dn5-rMUM_;=p;Z}GB_Wv~JbUEp z=y58vauP#(`48|~l}_1Yry^BNfVs}}EaW}t`*ifPqOsLIcawGOXLsTPP&ssHE|D5p z2#pUwNo(*_G&=gRF>0|8>EucwE27+-yf_tN7E8w#V;;=uK#iBtT5G>1AYCQke&5qf zrQ>u`d44J)_a-!Io@x_tf3DEs`jdsGYiS>%T3-3lj&o)v89$-! zt7@hlg1&B3{M&tr!O}uOwT?LgspA$0#d38!(hK~bf5?5^CtmCEtX416ZMhbS9yh-) z*{INW)#WvDXql)PS<~K%zG*w+rYu9A1u_sd74n88_i+h3bwQ>*&y3~JlOw5nyd9;0 zi*4XBW=s|Pawqy=FtIy-;99+Fg%upS_Br8g8?dA;_l98{9zQ*lNr{`HCuaK5lGrhJ z&M1+(W3SkPwuxD;wb^YUm%1o9sa+3!{xvXkp=P1<$u7|>GL#Rc?LL1|?TZL)QR!Tb z_&XF?eMUSRb$l2_L7YLcsc;}27}b)LJWGpB^RAN4yVlvM(C zOr*KsAm2FxC$&yYv zKKiZnGnc(h<=qT;KQ}$&CP`NS)6WKJCWyQ~FjWvym!AeRA!ci>i@+Uk1!=BSpYBO8 zg_uTm^$G3o`VfqG-%9&lA7SwgE*m%$NV76fqiO)8y?|9Dh8@KxG~_)}zLf@Dx9ue@ zC)U&70iRr^?i9T!FEH!jCX!OqyX7gvOYS|tul&2;0SrwM*TMRJYg6Ul0rtD4H_7KB z2jnhr^U;5)uduPEaSS4FaaE>i`LAXF-M0TyKXVBOY5gkx616BAF^&tm*Yl#9>GlZ? zew7j1iTx$!_BZZEPJ|UUzS+HWdgn&qumxJ@9c_X0a{(eeyiz`e(HCEyS5|L~l3|Xl zOr^-!3rL3<*ie7or(pA_3cg?E{_htB+$#OgH03lUK!kx;DvT?G{AgjQ&{-1>{A&_V zEKrn{>!^+MSMlz<9$G%7Xx8bU1Q%eCT@F=fE17iHPuGEb82$GFx@KEb%`=?_>KSj! zYuLlR_6#T1RKA4~yU`P|44NJJM59T3Zgw&q$KND@P`$r&;zr|yJvn#KryEE z4drR;lfmx*FXkmN;69^Sq8 zojOj1h5r}?{Flq;lc5dyMejFHqGuo(h@?if{-irMz2w8dEVJIclOymEf^rOY3_XLX z^2Qe;{_Tg(33Ry)pS?Clp2@gZ2^Z7nQEr~jj>H=IzTLNIzu71KGU*{sZ!H)5N*2*k z27&odo2$1klbq$Ha2DvL5boa!h(tJ#}p8dZv5`0;uq zD4i{78Mu%v=^+2Zdpc|kxuViVVpf~C7MQwH@$Z=*Yd=DpNmsus@gXGT=t+3PwW!IC zjV#6I*uQECot>LtoPr+co+3C!t#MYz0%;h+0Km=OXb|hEteiBGT1T(wiKqWm^fN>{ zoMEw#977VK#rU=FYNV}4L6$c&e6uzRYy;9lF#Yrtf!Xull4RFY?p_UvNwYo=5b9PuGARETuJIQpcLbmG6St6Bg;ITXrO;{9 zS+7B&_ePw5fOP(aUdG->(?K`%7}UH^t>bdCoET*sb-($1IA;Fi)Il~Z&|6=~H8aqW z6iqEM>ezwBTc1U%h?msJv_fuJ_diOt_b~|fxhMBuV2VR`Coz<4A++dS|m|3#n_5efZlOvnDR3>Se5e zY<*kWJ?xSGLT6zvKR!HVG)2j}--UAbA40iv&`C1=MajO>5Os#vEBwdv1GpKpvsIG4 z(o`A`i}={UB^v%96KNm?&h8kaEF%|x9nOCMa&Hr9jmD&9*7m#;y9`IK@-qhdi?mturE6>;v1?zFh%Il;r zx)wAi(9!?fR3{+Z7dHOFv!Xbw%>`IMT=hz+@vJHK;}nrR{~JhFj^S1KB;34qZ%UTp z9aQp0trTPp3^K`fVGrHPq0V;6dmR1ZQP8?e1Gi#pF(Vrt`|KAm*)iZS` zroBAbh{mLDO3^rE*Pg(`-EM~vJZKQxUsP$$7dF4$Ji5iCVB5`kE=SA7Uq3y}(nxK( zk5VN`xBiv(Qx&hIOH61VAMx#kG%FlD!p90Ojjzw7_W654p?&kLz+v3c zc(wuavsbdR2?Y!PCh7aX$r=Acb$yl)2|huD0wVD`AKV=_-v;RDZ5Hh&1HI^s%ex&_ z-GW7UyvX5$&BoOYHe)Jy95^B~LClCEh2Z2AFsmWux$$fAYv-~yq}$|I=nw#dJ!iCN zl-11k z=Oo=;gbsz)g%suiO~~+aBMI4C0dI*9MgCf}J{E(Pvg+&S5HQ_`${2nGIpPo@RGCU% zP0<0n%ulypxgIxYuIFq%wEN^T|KlBBIs2Dbzv$Defur@H}7C+)-Y*0W76@T&h7XCUGObJH5N6D z0i~XgCKQJ|c4YuRTvjli3*6p|eE@ljk@``e5img*+Kz-Z7%%rRc@;5lctUwIW<;N| zGU&Rzz!_^Y*)c*)F<3u?eb{4AMKAaUcT*6WBAToAYu&V~+WVFaNV-KGUUa)t6WgKV<*S8wT57+EDhcnl0=dUHQhRJpc zAK4o}@-q9J*DI=|0ro65>&w<5;CxjbDjTHZHlN-&>inTBT~O-M?b&kG= zl{<+1a=Lq-JH`lF8u&gmbAp$r>->Y^G9nhK_6$%?w%SqRbnf-lCwfEg4;w)UjDAz; z%(KwCy+US3J4&8^$w=_EM}?PIma2Q_J%Uzvu`%CMx9Z7b(8Vi~r${^@WVZsB(|3MC zbv>-EOG>lz)zNr|45G2J?P>mfW*nGp;8}^&a#@nZ&x?^`M(}U==FY|>`j@%iwtgoa zcsSqU9+~`3j`f-s_H%m+_Zm=Fa-W{HCS!%*TDX|rSvjN`if29-ROVX!(@8Twu>SC) zH9j96+jx+{`K*MW-X%z$y-Is?wQeeyT3kx|W^rZsG1B{x$b^E$EnH}+O66<3**KIl zJRV27W7JOlMU$fqW%kQ;@H^FDW+jCo-^O5@mq|;7LPtZfffB{b=jL$c#$H^axmI@B zLL1%SN9wgA?zn8(gw33XZ1`AF0m~XSQDZ8u?=c8;^*xG~`SbcSBd#pw7KFa%F@%y$K~`Tp0?RLc&HB z-YqD7jaTxi=MEySE~0Tow23w2y9EU4?qC) zqVDA}UDgS9ND*i#BJ*)!fsVFPiTZ~jI1{>6Fteh2|SPec!P2v#_N$6SsTxC z9iOcK3E)zkIt^cs8Jn)8SPxkdo+0BAzWjZXMN~^KQSN!_3*|$$UIx9q2c25FzgY@Qh;93#dYi3YA zFn!HR369A>j%sjhir-}Xw0r!+@t}U$-`)I&TN}gSeI=+!L(AC?fvXo{H1HW7kjw0iq^`4k;4G=GISC%0G5 z={^@ldZiotd2oyF^A;vAOfP}X zx3itMyLX9E;ZDrmaCZA^or$D)17y~rdv*x#8JdS1l5NxTfznYCr34=Gn-AK2J!ae~ zaN}@R?%mjNk7%B%Na^PH3klVlo^=nd2>5c5=j7+!ft_h$OcOh~$X`!=Uz`=|1Q)M_ zhX9LzCu~PT#XPhx`fYedO6nVQPQTX&e527ndQ08NJaFQLkZH_|ZKez}@*xTysyXre z2dzayP3T#f-7|>5;$^lD@QJR84#bY^|3JA74M991!Q=z*@waupvGb48-s5f%r+(Al zA(4Yj#pK`rYAPlSaT138YmC+}{8#X!XdfdY=$aiG5(X944?RX>c-|&PYk!?5dq42V zKy$*`qVW7xNSNwFDq&K@eF?P4Z(TC)E){|c@Lr@0Tc9USFrP4h#%rJgv<`x}!TpW0 z2yk;k94haOTeVk(g6dJhRt|B8`x~Wj z!KdSIyedK_>H6VE>7Lx)lpBk5G4rsfQB2!9^oo>9uOUud-s~$0my_{U9q}NDhY$|= zW-<+qI}~2{EGtYYwU8C|9iXjX9AbHFl9yJF;xvLeR;Sy*D>T~i+{+owhd5e1}zw@96|yM{|8FVYxX{glAaiMXNsa8E=Ync+iH7)_j`h^hvRM&gNBHG zlFopDba6o_eA;aB5k15`@UNAuFo&==Cj8=}A=cx^*ykaGUJZp1%cH;1!(Lvly`h@V zfXxTlRE~mXO9|2zW$ofwws3AQZSXZ1BdUb3%*TfIFE{e_r2fwmaWP9ZfBt@mEC=+nKBoIDC799j}us6ar{8>M(=&>!IW&z1*Y6y+5V9^>L~Wh z^UEJS38!*hMIjV*wGE5D*l2Q$O1RqnEK`C6O4&YDFWEi`NsFcb2$JkiVbr#Xi!4IG zF9(FCzKZ~CaQ`E$>yrN);Ob=pGO%LekW5wr`VI95V7L#e6(mQ&JHI=FD<@vW8F1kH zJt4X-S(@K9l}3u^1=ki70R>bSiOZOOKd?cx9)def5!KLyxOE~`121gMH&2;HMXL_Z zN^a}rb=bMXcBX3fo}uzXP3^FV8+{^iaM0<9b#k?)@`(!F;md_=G94<$qZ1SH_b}yU zDRE{WoT_y&YO~!y+RhATQ|E{5MMb2mg^48d(4uW-@rmiumH>S+`kT1a`G-!U&>$v{ zl5}?stPo4yE8{rNcCL(OI<IBF6_^@_M`aWKEf8~YTu|dU{H+r*v1`+KT3<{{GWnh1A0jJ~V{7=OIqs6;e~>X+ z4pP*?Wk|y+yW+jct?^=?m609W!BSn0nHud_dN;LX>v%R*Lh;Cp|m6 zi&6lIe;mvp@M$F0#_~eF0H+zYh8QLhjGxFBX#Y0&nkTQH~?Y^6X_682c<@_DCJDtyAbyk=n)ypcQ-LDv993U&NGf zs|dXCu=Kc^+V=BmIvt^VrW|^^YC*p23Kiv4M*>A52M)8dE zu1fM#AzQZ$v%a6HvxH4V5bA6L@?LJ+g&wNRgZ2K*S09dgpA+INBr6jdQO>_wYu{py zp6m90HI+}x(VmxW1hjV4^{R_!;l|V#EgHG_5#P`^EaNYdVJICtE;wR6%z&kUYuIN% z8aRlcj|dVDj;*f~Ow-v#nbgo1#7itvM96avy_GWqXJ`cf&b5jce4e7Fp#g1TiZioW zvyweOqamEOZxK6YZDdMxVUGQNYct-6!c8&PyEsL0xN+1B`^*f4m=Z53vcn=Gh{?{@aCz;8 zp^NT|F4yaYudqTNuz>v|NCtI2a9wZ77d=ykWV&g6Ti6RSh41|oN*EB~ zyDdbLu2G`lekaEHpiOzr<65CvoE)FZTM4pmD;a#h#d^hN)^LX z*|~$-`QqQ06x;m4QP9%#>wN_XM4w4#6lUua;BZPD6%npr$OXrF8aE|2=z|ToIRkO> z6JRY%hLept>#gfLu@_sgWZ)ip*GMO{%t>C6*(@k;5G35ozaB!$G^YktcB@sbm}Wq2 zg65GC8k|dNxgVFyQETK0 zr^aAre2VeQvz>nZwK87VL{kZBZ_1uR8i3n-&4g;)aZ+}}gn3+cxx~|r51`=_6FSAb zN+gxAy#5{A{C>+~7YEG1drOuBK#no0axmQf(g>~w(FMA|=1tmz#Yh?56tDG!A2U@* z@hG1&RX+fg`i33+E!DS+B)p2^+b)Co{KaZ|idO5$G^CU!>Iz4FkxU+=xy*|8CO?O3 z!p-7Q#y>!R#BbUhWLWi~rJ(41H2d*bLDLpQ0qfqYL^U2(y9NJ(%O2Vlph7UT28H<^ z4Tihm{H)1&AZ}dciCW5NGPHjNU3f>7=7JRu2T$>YYIK0pD7T{t@F6ea7Qq|SsdUsZ zsl;%AX{_>C@g&ze>qws^pnwSI;R_@ROe>VD#=I=E(dcvR3xBVabc8$1Yt2qmX|UEk z&hp2?gNy5>HnAg;D=2mJxdR>p!uY+$GTK?tJWv8Pf<@rM6D!2KKx{7i7?)f$d@T#J zI|-#^^b^F?Dt9My(KuZj_XL#`W3@C7_e<|QdkE*^3*HlwwT6t{B8IrqlMWvXn>hz= zZ*^gr%!sFx8{MDduxw5)0U4XINCOV1sYl-pB>K+i-{_`ByH?5@aD)g~Wl!G2Y2hID zeGhO!djXs+D^j@07LDTufgEe#usSGoaqp?=*ji7sxRhxcsLN7L%eHt5dB`ZU54v+p zcXNgk`i^caufO(rkDs_$av1AmKb5AHJXRB@!z-Mgl&AGItbOqzJHZdBYFp{UvK&Rf zc}OAyhCOy5yETaL#Z50~uX2msYn8vg!akJlFPqoK$_vt;zpKOa6Qt;`ugps0EUzr) zca^}9QadCeZd20<$Z4;pUC;k2uXh6xwQ5&e&CL|>yhB`=TA>P0T0Q*j2ksI&o|PI{ zu(9|pnEuUHZN%}pdYa{rxs7AbuhB{+NOsFf?Q3=mSEk87e>s=rb9U=)N8LmpZ+M;| zxsFE(IDs7(i-Wlw>T(q+CP3^Fv&5^y(o_he$kxWHelx>qA%dRPs%oFt z|8S|Dck5UJmI(&&u6AmJqeEd1xek}ej=D?m$s^Qnll6T5rx|w7qA!YGIC~g(6%0Jy zb^P^+f#kC$+xBag`lzclFAiD+jvk>NZs#3>^u50de)(&VnLl-uj!Ggg8W9VE&{RaW zc6+$voyJ*buwE^t*#m7E?mG>6L zKDQ$-2T7%u){h9WpWtGDZYBFV0C#B5=Efl}mOjt28CwZe=DF6wDVC?CE_0f zYDf>H<&IJ~_$3jzHpar((Wde?DJ`itbNymG{*(&4=Ja?UE>wAvr_;kuF{?i(-k#{B z+#}V>^Br^iJx&=NCNs86gE0k2`bSVfwwd!pR^BqIoDL}n4=-BB#q`bf;TQjHCZ!)2 zj1oBypffVpJ4G*ZovK1(!+e{CWs>eZB&>k;%t9Gat(mo*5=Fo<51kxb_0q#C z%+IT^M+~YKJ7trJ2yjW{OoI3&{Ps&E1c|I@r@NSlj#|QeO2DC8Fi#n`hgC&W{sbiZ z1E!x6QJ%i@4cj2VjIAYuE2yCe436?dmlW`LH=rV`7fh7^38VVpB&k%oahwA+6(FJ2 zWoZ*$_`v_?o4_ZEc*`sM$rk*V0d(MznsCQoPpQvD*nf+GJ<7uV2@~=&Lgc44jY!#V zn)k$x>0K?W$_v$XFa?NKFY~Isiw^!xi`bkZ1ey&U*IG3~NeRw;W{1S^P?Zzj?!ipF zmO)vX`Mn+=VCM11OZ>G-Zqd9}RUS%UqW&8x_1N_0wGjf4CtC)ZZd;NfxVpT2yF_|-g67CbkFbsLgXkYGAr9}M4VPWZV^HvbcheUt+1dI= z+Pp#HN(IbQj^A@fUY9C!jo+sxnOt@kL4y+$^%~bx3xQ)gf+xOBl6}g|lkdcV^$p#> z47Emo7LPfxr6*c#7|*vLw@Z+utpWN)xT8a1oD9STE1dqngN6L$=l-k9C@;Fq2tmJX zK}!&eZXkMQ;mKq_Qo8?kK{gjX4eKzQV*001_U0M)?uyUucGF3q%F`kn`+Lke7SE+z zw@QQgq$s?wW;IdvhUu`@#^Qhn`e;JAOkd}*tw@VA4nz!CLYemg=tfLiEXd0{*aC7$ zSV<-&#HUA06OdzNlMy>0_A=^V6zk#C{eKki>jTWZbW{kDz&My9Ct8hb)Ec*Uro4#%urHSspI6Sz5R zX#5%F!ln^9ZDt3!c_rW34e`oNS48Bqzl)nmOwlq2V7ELpG)$q~s9Ck;18z0IWHXB9 zKc!T49N0cqgz7dTjoYHUOQ&PhNlLGoCnB_LaQU(biyGAX zM^GXIz^r@_N2!#oQKMKc;iY1MT3xkeJGv)aihILP{pZl+hCJYE%7=8;=IEu~Qp>gE zH{cAb^pkkeIGtx2s)q%_g@U2;Ba{Vx-rxa+)S7FR#Fo7cD=Ip!>2lA+wPyv^7x>Iw zQ-0{PE@&*88ZVfr4GrDqR`;^pyOAm4${cM!0ZMEUvHQo(!06~uWSSd~FAnwV`$L?G z%Vq)od?yEH3W4036w>&jxCH?|6w71a7~SfE9@N6L5GDg=KN?PE%bweO*o;TWy;pai zyLO8)hB}mbjOo3tS*l!FGwUY?HuzeKUO0_Nck5%sqV#d689NvT@wrCA zpd6JwzFjgD68}9Un3}h0m_hZhClSVvrt=QRR{(}UjC}&xoKzPFX`7|*h+@W5njz-V zGvinEhohC~e$!r?e8M7?cwWaXn&8UJ-;yOlx>mks)jl@AN_)HCc(6yE7H$MN`Eq_O zpNH7bAKQRR78tgp6l8J zbg2xRB29|zq1cE)zYV9svcO=v(WC{JYO`A>e*1Nil+4~W!~W?cQ^70BiXsdERr%^n z{iGXzb|BOX^(=}r`5RDrh^T-DCOz<;RaF15_UtZVS-X+&p3qI> zaiT1LFxyhh+iGjwxVXNDslQn;$|CN`F}l|~hrxKGw1;KU-q=Lt1qI#LcEla+Rd zwKAcPR1fW-M$2uyJIyG>ULEXrAO$_LJZYZHOa^|%9x2fn2|5&5((2;nlD~N#DtfL$ z6Gr+>!z?VK{jCK04W+9wt-DRWJ^AoMg|B zG)}oo8aQ#!TtAjPO>#9vfzypapCf-69YBU3GzN}1Q|3*oNkXI4Cg?|2bu7~W?+%j7@yu@smuMjW#z zgl$LRDnr=?TxZtvRLjS|NSVptHmqe+xvWLqKZRV-k&LJ1^yV9j0AckKJ`H}5%u7;O z(38GsD0BBP++{@7rp*!oO*INPS@-N0i_2FOtrO@r?yq0LqWJRDveklZSLD_d(_L~eWb8OVSm@nBCvX9|FV2fFG;dr z+lyN`bDPN35m&(E201GJ@m^;Fc01P7hE7C?xO!O zDf;D(|D@9GK!#m8BS)8}U&hSF?w|c%Ygbl@#mEf7lU@GfMZ#Sz-jY4dPSh?Cdi-B8 zoc~kq^j~*YT2q)r3l78ZFLL@h`tt#r93x*J#ZN#hZzo65izsSmhgy~Oe7Vr-hiL%%H z#qV zT1m;$G%@&9UaN~ghdvhGT@U_y!D@9ChG{LoiVcu@SF=Zc18_XbEewge5vBffvhe?z zy)(X&v1F9&NG6o3ipWb+kJd_4G&jf@5uCYSC_Z~`$z(?^29%1U;lC2L1V7d$Tr^pR zIrK1oW-3pJTH4B7z|Dav-WC<^3Xi_iLW;6hgm61%bQa}oMwoO1PIBV4)^n5IAVETF zx)FjsqHc1=?2ZKkHAlN=7v>jTgzta*jC^^l&a_f-D^N$rP#QSP*j9UCZwrbEt_7O$6gG zlL4aCTKl|AmXiKj**J^f?_2IJf~0`S8Ie74vz^II^?H;+ceRb}gX~```5G&xi&h&3 zK+3#mB^4SR+)YVusP!gjSz0AmP+i{e_1^4^_Bhjll*gi-1JS`kS~{ZG~;) ztmI@NbdcGPY)*VU^<)_lZ9 zUr=M@VXe$BoTK@OjUat8ZDPO+CQi#;On1hp27*|0RGu^(J$28ao9DMGKO~se+Cxic zELMw@oodpid}i#jT`d%+U;*w*$hBgk4@wkfZ&15#UyNjs@MlN-P(qB#^<<*fJo%cM zq`p**2)14!YUPPstFr-H@(O_l@Yn!1h=!)Tl=B=9#3F%mul)jNFmLlMwE;K3vr%UO z-bd>DWrV%l-p+<>JZO0GG!m(A_A^S`n%e5oN10u65+%i3XJGg>18tn|g4^j_MUkb& z8$A(Bv9{*rFL-1F~L@5&Mh*h=K z)i55>;9g=oSisR_t?rbuMxQuMg?VXJ=#%=2f#KYwliZ5-TEz8F|3n8D$nLv=qY zdyueF>&J!;Rr?ZwU%A6vGLm2n%0<*6b`Fs}>*(Z^W3yo+oZNgug3*0+aeewoz9xyz zWkjd91dJU~DW4dU>6kG>^M0flmx41YY&IjgI$?grLh|1Ip8Lj_n4f|i@D;>xwmwMRTFw@81o3fQ+;dp2 z#KKDsyxoJ7(Vd?bULt)*X3?`4qU&a=Il8^UQU>&wd$`&_6y1e)SzG_qiW?`GW@S{VAWAhj zy?QK5;WA9T34>;EG-Fm-_tKx@{>S>eF8X^_oYWQcWup-PEKXtxmn@u=x5y&Ls%2(O z(vKewVN*)+T;aAtT&{M`+0UHQnO`nEQf3;C`8eaY+bO$*$9cJX*!!^DOGoB66*YnEy-y3=VP-M@7?DT(2X(-p186>1!GW#OZJv=5 zSx@V42_wgUU_gncz~=22ywCF@)KYT62&4j3x=UB69?k?SZA9Y?xb1$RBLdL6!U-d|CCU=Df+)>P6*43oVqzHf)$>}Ui89lyX-@W3(;en9 z_8IsK&@Pb7^GY;5Br8B{Bgij_U`*3BYrz4zz}lw_qpk6(v~n8qtst0V%9PUuBQRFV zd=Y~%sei^mU?@T9=D>j(&)Z{Z_J%u8Ku^x1mY1XO5sAlYsDq&-mMc_^_t!bbnPdI9?5J-C*Q0)5+ zx?Xnd++BNLIHF-)V!rmq3`-M!yD)~EQpVInyt;#_b`MOj0E%3+p?YJl+QJX}v+~Vv zS*TEvFIlK>s73Q?V6VX3sNBn=q?p}g2}IL)GGj%rl+jaQii=A%tSStOFa^I7d}o|7 z;7*yfqh${8U9!Zf6>M6B4Hg$cRrmOKE5sr}6KAEP8|78rT_%l@dS2dp<~;+DcI{+u zk*Vtc>sX?cnLi6wZfJe|PVlSwh4R}*Lc$%S6$4Y$a?@ldjqX}n&Rx6aIC;vk9C9}h zT{4ji+;9w(XSL{FY=+Pop}B@qO7GycfJuV-LH?6tyYxNGy*{Ox^I)I{=ZqFB6WX|@ z#}XoK1muT{egdI^t16~=t0F+e=Q2Lm%8oub_l{I?{^1bkG}2b0AspiJ(y{v2DYnXi zBDQ=7uS}>+-CTr(G*-rS%Z9?_J6YATCqG59$G8^Cq?Qs|ckWYW1oqFrEyS}2i9}Nw zkM@b)785`Nh1k5$mpNyzlb2DXhu1Fjx`k}-a4e&e5t}EAtPVA=dl!~8K2*U6RdpV{ z6i0=zgZ9+rekoE9WF&@geEW~h+qu}ra40pmMJDpnkSfm|G+PH+2(^_#UY0a6&*B;1 z#gauQX7D1pmX=I6)W&&Ao3zktc-X&WIQKvQa8Ia&rC68lC60_D(d0OL}Z>w!}bKk$v! zN;jL+OU$g8k<$`+Z7SOVzA$zB6hX*pMmhKBv+`(V{^nD<{+W~PPQRR z>ozQaNs0!l_7fnMeO%82$VI79Iwew>!tx1VkW9vg75nBXsH8m41btcYXq*vnACOcT z=vR8TM}R+=T(iq{NZ2rQA+uGTBhdt+6dL0T4D~RK?*Y;^LpPFw&8C2w^<0Wg z9mDS{++~<5-1c0Z8%>_B2<%MHv4mPj8cedWkrcO(`Y`IoMl5~fY=`eaJ0zYM&!=Jn z9~SExV#jznQT84MXO9Isepg)XW0Qxs%t@bEaKs)~Qeyx_rsV{w6?fl|h8LEWSDG`0 z{-w{j8yvK2C!S`2=|eiG6~8yr-$}7DLBW0z_U|!qMbes;N5l($8bBaQ3qIsGF=1c& zdwQMY2`@Er(^}9`4MCBAPXtt4g5Rh3L!!pvHr0ezXt~)5cArVt zM08HpGD@F=P*uvB9Og{_7fPpoIx!xQK_Le@E^=0P(eOO%*xh*l-RE-MLP_FuSl@TAH~*-f+C zCu0Hbz}cxI$`8dqmZRmdcCa8GNj06`v_<+czn~_ukhv|ZZTC3W>EA2O3G@cZ7h#*^ zixr?4-PeqO>S7Jb=tNW#lyQ{Ot}^Hbuo@7ePnqF5Klk61&(cf8quFAU+$G}6iMj<;t!c`uRL zE2(Z=nBNuezz&-wzxDaCYF~o7w$Wa31d@)C?SFZ_=q`Om_Jmj zvKpal_Qi+Cykmc-9BhgKVrY|###ThW!E??2J7szLLS=)jOH69NbdA@j65VL}zH(YBOKBP*o0G{N?~5U1M{WmLP1S~Y(6R#ttVm_1s+0ug2h z53;qBBw&;2Usn(Ld&O!>k(y3JWi|nEfGtcC677#d#l-01dtxLW`sW(zws|#-zMRRC z9UJBYXyr^{?n>*!-zc6m4K<;X-<++3LSoYDG71h z{JCOAk_@$fdGODtFwt&t!)A`E7?K>pcw@iQ{L?Sd*QxAgUp|^@?J}UI&uCDmnYf7a zB(R2MfnQB_Ag{!Y_QZa@L+agH)#DmHt;+=+Bqc=yr6+469f73xUPc0l@WLGCs9jPg zmtuIV(2h47Zjr6eISN1|)!fhE+=|;OV*$7*`YCgB<9;d2X#E^$SUIt+h76+xM}9Ri z#PrfHq=>M`*(mu?=Eh5tt(I{-do(GuZu z0(6t6yR6}wPis7jeT*a~vM3v1!r5YW?R}=<#sM$Nj0(%(RZz2xKTw1m;{_qqKV#j7 z>Ol?Uh;$o0zj|M}Z?1vM`v_yrL;_f9zcDfk8UIJO?V!UsKV+H6s$ljqIc<+u!Ewk* z+mUiBF!SaDA7mb!EgHO?;vZ@a_O4*2TkUMgHBza))!$1c6{=NaFZb-XHnIwD$B2vD z&769%bDLU%*K~W@S>o{yUU9`)TfOk@d*d7usC?feTN|FdU~UY8EAT%7NW5o=Q6*l-Z@O-I6*iRI!sNVr%E2pAevgvu^7DQ3?R~o` zOC&#cI8}9w2FQ&Mu>;Q-Pw6hao)kpAIF$c>-ia7fpO3>4uh~E}JB`Xqt z|9J>HwI+DyJ?jd_z8|91yXe8BHmU2P|J)yz9^tk^de9K&SIY}VI75{ok z^(;thFk}C*yUG%#9ld84)0(22cuUa-goZ@^WxT_J7V^KfOWlAVI9G@UtGUicQRcS4R)W+LFk6mffamK1GS-`mX+Y)QZQuj=+ zW$Kf3Z!CTTk0BF_s6_o5J9b6%MXB(IxkgkT`gNL$@>YDW=9LhL0Dt1t-|~*tRb4)F zSxqk|+G)Qt_e_!bl`a?N&?6g^tU4_}wXKpe-_pSRtTHfSeNA;4De=G%*Es6#l4HoS z8B$t_x8=t@yKrN(wJVUCAU_*qO$54bsoXmqn3$to!Ig77-p7qMHxQZnJ@2 z(oC;E&L_Pm(>6|A9U!%YT_u@-m@m2uk#1B?#0bwBZg{Kb2p>@YdJh&@7&`d zj_&%nxTlOManzFZ;gNbTGfTiC2ZicM2PJ$&(61ez@;P9r1qM_4;@#CK-CCOZ#-N&u z^S9JI)D@#M?|4HU4!x-#Hb~K0J}xwgX>4-)JSzW{?P?1Dk~=7yYxJs4i-FCCL*n?7 z8r~h{slDlLrt2d-yqNSucxg7Grl|V2IIGzB`2stR9t_{K&=)eob9JevG-81w!H_85 zcWh3=sjYicj2?&J2F)-cFd?6MFsHjEU!NbkJ|QW>`+;2!5qfbP+yT$KK4H10d-^7- zvXd;vc$>G{kRq)f&e45POw3MC#AosL4s(&T;O<;A57fn#z3iR09@S=OWM9gltD{jL zde*MiRHF~l{5Y+9Dw3BMzn$2eaj>8@w{v&0XUuPgN~7e|3hP>ui?=t8!F;>^fq~|f zhycVrFXf$iegco%*$x#gKPB^=L%-%@m{OFJdF2WS#CqBXNA_r-f6P* zE+?C*j)w2r%M7GE!ElR`R$IE70bCj^E0PW=D2=^aNyg}<_@b8S5RGw@ImYvc7vCe2 z5L#Z{uW5O{r@YT=Lru6}DEz4C!}GM;^M&{6MqQi<8*81iy4Gd$u*UM{W>^3GWjz}f zstJwHA~DLExELLmG(WYmQ_4$+I%TzI)bv!KD7<2-g~`C>+}MCfZ~J)@7UH2h2ALb4 zjR75$9}GU4<#=QF^iJzMJ3HJbiWImwp0o9YZSjww1oP-*^@CGFi_|HDClRfcTF6q+6g$it_HtchE}))NFeCiZ4>i zd>0-XUCIeg>=;tBw3!8BiI!j0gl;g}3$b4COq%;i__HODk-0u)P{}lsa~AzvlyHcz z#|sx$E7AKuhEr7n-rx_tJn!lAe}TNjjLixR0%}Qy_;8*S;kAl`2y+V zEDM}u{0`az^kY6y7(BwQqx}p%0qQ{MQ&X~{9d6$1R z#=D97k~ypjEc)Ri6aDm79bI}x%cV$wX7+nS1lxIex8*C0r(5{yaDEbD)J@gIGQX_1_P@;B9dD5(KM;zsbWdG zG!^z0T>~MN;{so8OnHEA;Z?_SZy+HTXS2+3k=vfwhkhO;9;Ncrz$y-V)Os)W2A|i2 zU21dWDdE%B{2>=By~brr2-tLQfYM`OgKpvmek-+sevJ+DhRB5HvN?jGhr|IR8=7NW z-9?Ax%@v-r4ZNg#IILuZ6D+7#)w!qT#9f3$~B3!rt407*_Qc>ntC1 zeJH-+n#SLM4TxRHHz9x}SchJTtI6o_N>@GxGIf7v92v}fW*jL`y;db9Cjw^JJ=RNy zVB!@6|2+%w#rqEWL;}bQw8btcI;cKQNh(zW|E7f$P;n)>T#)^rW&9u#ORirqp0}HH zASzrc>P*C^Osjpi>xf)^k9EDN;y>%d9w#Y6^kFw9GzB1fubI-uR}ksg|G*~h9XIYj z(z3+ZL#1-^+ZZX(fvv^CQp33`&Kvpbh;=qA&$Wz-W`q|21bbf!oRG3`8eJ!7sQf2ntq+) zN_{|GoXMNXd+|q){@>?Pa*_)2t!VKI1K2aftL>F5DPy9&hMg_nL+)hJP|#5LiRzT^ zs#aO%U*v&@x_Bp1jYGw})5bPh?uqcb-c#~(0VK*77G6df z!&%*zUZS)x%0E*kYR7j5u0w4(TC|+vJQ{WWqt#|pt#=NI?iJ6{7o<)X+H7R(sAV@~ zc$R@5ExEt1vm|uiX!^s|f|89PV2-e9ut?e3&k(_`o}!_iRtbz3J9rMsVQWVcZK%Rb4C3;35p?S)@qt6kx|5|;2(|JNlHXZ!a zt;OH_xNqt30ders$SR6sAQPoxQF`!Y5lWHOb{<>)pRG!7?mJ+?dTvk#h(UmJq(G`P z`qE6UMPXsWluu){0R4B;)E7aU{{dM9Fz)=2qqxaMloqf@aIvq|AwM~XTJ9K|Dmjxb z3^cO7R!6S9FDJ89+_Yb90nvWNeMM-t@?6J1y&b4tj>1%Ppv~MdTJ$6&j8?hw5H2Xv z?d|ZKO=kGA3mn8oR}jk$Opxfa#zFM->rpwmx&j;-c+T=-WMqh(XhI8uxLvy_g~7K| zm%G0H-Q++ShW(0wfX)`AvxGNyUVdBOJQZ~HZpzKtTt@mRmd2#shavbC0W-(y(SzW$ zNmc|Y5&6Iv&e2}`=3C5UGP=+0Yt9DUa_W|uBqmt0RxokVj1OQi+$G?evg4eUQClO`4OzQscaRK6Aq9P!{j)g0ByKCnJ!(Myq-g- z@^3D|Tedlz$zg}jPt>&Y{gC1G39#4dH(&F}hS&wG`oWFgf#3b1_53Ecd0m>p)oD$K zBmm=GKfqWfQ-j3vgm$wReI9@_v_tU6+Y(i&Vm1mU-~CuiU;FOfh}*pfzg?%L%39ne zg+VeR#yJk7)E)-ormS||s|g(THNo6jkPH^*EiF+a{1&3TeCPhZLV_ZB$w*d~&aMxZE{K$T~&j+;)eFK!c0LX;#V?6~&I%;2L zZOO!-OU!ErQ`ObngJY8jn#r*6t+@pTJq++DM&K{Si#O-h;uTUu;X=qX-ZR|w=g=^f z2*$}68+)q1yId;87tjcqVW+p_d7bYNtk_RgyyDZ`$zCIP)l*9uC0?v|OF-xJVMFnQ ziNG1`&Vgu;7Z2-YXo5jE6YT*`Tjn-3z4=;Qn!}E-1K49m5+BfMcI6Y{0`s<{CyXb! z9?@-rARdQ!N_ZHi2r#DPMm57tz7Pb8Q*>00c0qsm+W(+>uWi1^x4*$h=5zEjbf*%| z@ansHg_2tmN4bHf55d;P_>6Z|X!5cO8m#!{*8QpM0EuXEwIw~(a+MzSn&BOQwGII1 z0)qxop~CT%w0dv6A@qZS`JD2@`Hq>B_G*QM(kC|tN#-lrg|CHtYnI(5dl#B96wHIJ^={%L%|(Ly<0l| z8fqO=bt62k64Z7sg(+#3qi}+9!O>(CM8CneuWe+$umz~YLp+urVj|Nal4?9y7%)#O zZYq0Ms{qnbI|S3vmzVtMoRb(3$Mcn{2;E_ELHv>b@1>8l{`i^dxFvWWfp6u@(@UwP z3!{`->GpmH{P@0@`avN`Q0li{{R5R)aMi3F@AC}htEx)6NLiC|yFgEo9-Ms9lWuOa zY8TTxuFVbkw%A$yr>_R&rd93yCrrrZ@7L65K(mfkJ8}mD$L*Y->(LSp^5A6grZO$n zA2;DGP%kCjQxxJ*Y&D`{msUFr_k=n>v#VvD#lj7rJCv3Im~nXA`v9%$7is@CmV0}| zVa!R6Z4sx;oJ*PRc=U!UTiz*O5}%73M`hnQC7=FI&n06+Ljks&V!V}|;Pk`CVnQv~vzrYvvq<3DMs67?Egl(BhpVirDE<6jmugtIY- zlT+j}Hwg94jFLyJiV}m};R7TtgL5zpU6R*){T7h`D`9j`L5)3I8HxhuN)>bvPsK)i zMTab-SLl~kRS7X=kvb}b;9%08ttFEzTcq&_A#PX|km^_^eiaU4Z|9Ue&UB}cSZD@WL#HTl(jQ5-aMstQEO7rKQay(vL?vU;9 ze-iG#FGh`)n8ut+p|UM-8|77pM6Fl%ma}tmrp{+nc%BhwlaV5G6Pl6Op`z%;9cjN< z;JR`%H<@HnrH{FPpAnc&U#<0dBPy;mpGRu(Em095vIAv`xlNjP%l-R0zSK8f&Tl`Upjqjuomv%LNtuk2d!afw!8mxE=}Pk@hYf}eT-E*Jm+ z3=9+uJQ_MO0s<@)G&&UYEf@eS93~bv87n6|4!Ll`_yjH~8#{-xfs=oHZeD&h2E{!g zk%tbBvDsBMwUes|c=wfn0f9krIbDf5_4uN+gUBpw`{7*UIf8~fGu zBvsN#fYeNbr#{UC5TKv{aDvdE0B0Czy3g-2jmr%}7<_=|oqll^7mr&wH^CO`uOX08` zey(4IMT(Psomooq;WTd#o`jQ?7h;pSKXl%vcabUa3E*2tW6pI^752vN6X20v?;*rO z^YX#f6{a6wl4)GY{JO38VBYD_&2lQe!q~$jBkZ;}p8zOrl?9yK>k8_rSSOh_FI%fM zSQ-bGM?Edtv(X`rh$DO3KADi{z0fyR zXs3LLSfPWR&adjyY#zr>_DG2qMk%6M8Qnc^Xuju>PRH_KYJs+%!KNmrhlZnxkNSdC zRq*wN1Kh(-P#tTte;^;3>aL?$b1}8wu_j+4kH=G3jkGMTgC}pv>|d{cY;eHImaPQ) zdaaoZL)o2;g-G>=;PGV;@y@m&H`T{8;ol#8(yT-hyEc&8H;4gX-xz*%64ZVq5D86A z3Wd5AX5B&UNCj9Sf3!upAAFQ4+39=cQ@X`z;#IE{h7n**_HgGK1Eidz0wNoMqopTh zEo^V9z_Da`U(!qP_^S9oBIo0Fi}HUfe|{iJWM`irj__^U;!sBAMg`%@1kYR8+_%;( zrx9q!fk=LO3PR6eSP=uI;L;#(fWnpUHQQykQS`a@he12h_o-@n5kxSjj%iIo&k-N5 zv{-wkRbs<=^;_$Aw;9O6bnmTTMmOHmS2i1@Fo=$YVNG@JZ@d+XFvz(`K&#iCRjzvTt`A={;ZcY;3 z{RH^@!p2G!S=Pa%sFj6~s(5nrIi&cSi_me#@sy5m$|vy4cq!wd1u~y2h8ZFSWDp|U z>76v_!lWyrBC99lb7gk&e+WL0fQH3fBHH9z@ve;5#A&A$<6NmDkj;D5M~E|sOL?H* z!cVzkI$|f7DhRf{F{+Qv@$e$K*h`6bty3QrUqPK- z#W+2)>up9q5qp5>Dk|O1vp?g^Wchg3B4G_?1e){#Q$wzriT9o^*K~@Wr+O5Jsru6N zYNTf3S)JSJe>eR1k^Hwa{P#8Zy)VN$%#6}Nc0|fc(Hv?Na-C(UlhD%@y}6XvQ5#_ERDgkcE9 zuGq_7MT@&@ zDHMwCH{JW_KIeSzH^wXD8_)Co$&X~MbxZDb%{i}W@T2sSBAr#nfMZ)@)%WI-*{kXO z;9Jr+`+k9r^xEGvH%jkuKDx_vip3WH1fC+R7Nal!uU!-TT-(LvoJ<-NDu|6gx)@9^ zW(AXzM-3KL`m~#$!ScU*xPLS4Wc?(&YU2RjN8HSCOv|1^0H?}4vKP;v_v$V&-sAEc z4d?N=!U*Bzd+DRWunb3o_YQ2gy6PUOGIJ7?j(#Y4Sx00~I(`GZIs4O2{~x`ZbZh0~ z>t5OgnjsX_``JE(>Kk((=Zb`fRM~X4tYM+-{WOD2YZ0ga9e*H!Y)u;4{=ogd4td7e zg9iBVAOE3KDK6t!y0Q(2H8TulcPSJBz{>b{i*nZ!tijmI&mS3pl8w^eeBk?wH=X~L zzeXe5_hnld%LdX4$@1qUSb+j&I52|lHa@qynC;Ncuq;IQk?Ca?Y4@BLfBNv9g!*RO zSNn43&u;_iMAmitfU5P0(v{3g#-AZfTiqM!jACNSZlm1%4dCngr+4L4=xThf#W&H# ziXct2H_XTNM_o@Urz_=QZ_ShdV%BxNA&StP&F%1$n#6(%FR?_m86&`&e`h@X?&@D= zImBFwo2QJz87YZJEC4fD(7Srt$6y)0`%~DHX%uqwSn}7J_yn);hl&Kne0#p2X(O}s5c^5XzTGJ^0uK-2P_?S&bvo?QdHsU}#Erj=Mt2H+XT z=w9=8=JOgqbN=E6K}%U9yxjWp77V>(P_HchWbMKxN0?I6pyo|+2 zqE(BSUM3AlkvSxp`MG{pT84lECzL1#0by;0w>tXlwP9yUVguo*iub2ijCy98Ly@Rd zibHHL{;(F2K0MPTyh7&-yU&St%VFyQ-YWWmX`ML)K-smc&B;@xVv_n|JB>q_3OB`N z&)NMHxx{(uZH*?X8wfY?CRkdWL;W?5Ylw=xvNVQ_=?ud&xOg%2@taDz%=Cm*(gHUM z-UO;h0F^X$yxtj3tX58{#k{?0#FSvpb7pZ_rxb)OW>y`@Qpl^~2s%nmX2MFcqcWHw zRzog;a;#wFm0k*gYfI@WGl&Gl$QGBQ3Bz z=t7wEgwiWw-F3Sxry1RQh5Tuj(*4?+|0L}W&d}H2@j`QKv>&p`n2PC`tFgJ_v}7k2 z7Zl%ZoGO)G2_}Rpf5}rdMIn6m>?Y^KBT2-*yMLdP-|OvatbPnh#E;@fVF-^R#=E#0 zUk=O>8WGDyVPe*f5Q0_L?d_gOlOJ;TabQGt18s@GW};efuJ(XTG5cNjY46_N;PyyV zu5d~p;Nkg)OF6?Cx2zMTjv@y?hrTAlUJT~XUlVzyd*|OMTm)|YT%{Xc7V%khqbCP! zJ>2z5^X3&)bI#j_Q|n{1YHVufvYYCxT(BJd7$uEK-ESCTdXfPnO=QHP!uTo?1s@0ebT*G)HY781VXplb3(V)n4VzYBs!j(8Te3h4`81B!ieM0;* zC!aG;BfX4Sp4p{+}CVmSFh>iTl;aoP>@eW@v>P1XBdXytd z&j6jwla%&eij1M@OaZ=HUAk)H71GZ)I*=WN_4j&VoN*#Z_9D}1r#x6DMFQf+%HC0Y zNYlMfUVzZ%dnW=fOOQ?U7^GGrJ6|U-PZ94GT-q?>Ov+69!)bE2 zoa5+%A~Q|F1(f>BM15|9NYjJZ_(SVRidN;I5)K>m7)r+4(k?cKV^fPn96fY@#aYyK zF}k_Yf3wZ_qY;PA2?2LhrS5+_(Ouceernn`{p(TS3Gk31t$YNNKf2TplNEIGE$gQa z=d*a$SQk~c03RoCMd#b0wZqKPa2ZSPmysxS$lkX+-EzbrY@K7QO3l#-yyo?wLJ$?? zu6jxCJ!{$s8?LW>Kr;I!VLxS@79<_P8$9un3gA7_zJy_IIN<@V!Vq%3d86sX5Q(b< zeV~@YV1D$3=|;}w)``I2@#`N=yOQcCLsDOU1NbEV3Cw3gosPQjb@17BI)1@iFHZGn z3Zdyps`m1(uQ&z79mvHki6JYv!!QDTAIm3}TFGkeXr4Dm)Yw*>eUVe9UCdYX+J=N# zM>TtyhQgq zuU4)4Mh6P`4Pf`{#AK=`WeWZ}F(m+Rq&bD5<<0K*2<)>P&ZT|Kkc>+baoaqUpUd}p5owL!(L>wL#zXtp3 z7-n3haBs9-Gr>}rHw(QK!~EZ#My!ZOAKn~{OAr6YVJZH&-e9Om_b~d`1b@xt*L_j2 z4%0)W5k{TAJ>b_czoxTr&TR$exKRG5D}7nBJvO_?#41!8N$xocAA_=L#6;N<+v-^7 z=7m#t{!4NZY{?*YTt}+=1o&;y&%CL_xbH>3VAkvx%!+klcp6Tpw~6*yV-fU@ni6cS z78^!IO#C{PPIqzDKK%HFhiUu{G}w`*^0z2Iqr1i9hO;;%A)O)G3;0viYOFJ6oZ#Bl86t;dKVe)Rxi$wHmuv?KRhTjy|FOD%UWQ0&GBiIxn_`2_b}^6M_jArR)Fv&a7xWl8 zM2)QEzgxjuv!|4RES_0p^}P1W?oyj%G8AJ6e?D7m!b_EZ*u}q$Lo*U3r0cAz=(Jhs zGjnk94r5z6m19v01CKH3$h7grKkw%6+vOBpR~{9|2zSP@_l{XxtQ(31lo*qLusi+N z)h3dRl9}kyt_>PpwYAHsMHH!vl9J^HlYa8Q_{YCBVvSc^R*%;A>$=*XG==?Qr#&}g z#uwrHv^WYa{N`sb(}t1a%cSr(z~kJXtA@H$xk(0I#5#C2{bx9R0&nXEZD>io$teaf z+K!(52B^n)>L>Y52&@{98mM#}>x_g$!7^Wyz}#FgB}eg5+QxxYc55VvV3%LSqS_LAR(LFH7IDQNloq~1C^nSz*EEFuY*c`F8CvX8p*}2lmJ6SMk zZANHNfr)o<2lLk@(9U&g(!Y5gGm+Tn$=H#T?XA zenM-zE|-({)-%cuKgvC0`qju8sqz=81O~bFw3=>2tvhe>ksxXfvo~OU_685=;Aczh z=oiWJ1XeC#`JDalAo`ZWj|=>Lg2*6yQHH1kuPQfLoc{&|jI4iYIzx3U@WBWBKYb8h zOubKMjU2+w$$XzLd#c#>J%p1?pSgsQ26gS{o-b5neon(;3I4SqhGmYS=g)#=+E}9x zT2TYhAByV$S@F*=U_aF*~L&t$=46q3hMii9vhUGLzllqX!LF>dw$HPml>p2B+D_B6}~;$`cxWe zr2I^kk$N>3bt7oFt;C~VQ^^LgRSQ}q41QtBASH_?$$e%mzQ{L&ZNpT|R=K4IlkZXE z|Jmaf{@%p(edWKCW3Pi9yB9Ha^vjB?^Rr9#uZ5dcvu zP;C#=HD7n+`pYaRwpwO09NKBxgNk-^!H1tEDy`d6z!fZJ zl1EAK?gzg1h#KqbUIE>OYET(>jlV2<1j?~a0}nG=9uREk-To-a^$xNogy_gNE(HdQ8GFr}9p>3TYqwhxg*t)7UQgkN z6Ubhu5!ip}CefaDe5Q9C>?A&rM2X&zaO^4ez<>AiY$*7x`RZEaCI+e4)ylc$Io!)_ zeBw1PBiaO*gTVQshv(aMuP;<`LE^E+B2~ku7^c~ObD&0+HlW7~u?bv%sGrGC-~LJc zj66ZAp9~j+-nY6oQ>BKJBsU_&L;hHw*lvGmpPt|A#m2$|3+~shOmjK2hcn6~Nk~`0 z7x-pBV)QB+p4G!LxvaJ=l64j=*HKX=Mw=(3@N;qHwYpz}OAFkvSGZgaLfg8DgEbGs zd^sfqNkAlXv~h1AY1@_GCfSCse|nUjCu(8B{L&ayplDQLpExMVwO{l&pxK$M2sNww zN>)H?%$nq=Suly4mx?n6956Jjt@mXe3LM{}ob)=F;zy`P;>1y;9rb8%Fe8h?uOPD^!-2_0A%fjM)$dn{C zB#~*r3KziCEKchp9tb2m($|w#8el9^40c$|N}~?FPbrXOyp%Y>FMT`u;>d>RlaNc9 zvi-oLkREI)KDjW0n6**T{1D|+Bj-}ptVuHBhFJk;9Ou>E;6g!*qD#??xwRjz+DFUQ zWhKoEJUz~J;^zj}y_4C>-f{)BOtoqrkK%N6*V*can9PQVq-w@q1`@$VG^v9-zpO$v zj`7oe_AU1ad3zE%a2ho)?$&;B%fJeS=07IY^U8s&mco$P}!+7w6Ht+7TG0UkkDQLo+ z3p<=#0L{D7=gZZ3S(W|eZkE25Ma49u0)Y=Bs3YgZp(Z9wRk6zM2Y#(ilbZ0Pl1{gK zwMmx~K7jhnQ%Hd)9Ed{_Jk00WN=gO@5QoAL!v#4Y3?g0&N~oZFOB zwMY{(#LP-(MMUzx+YF!hDL+oRC#mHZ<`@(1X?|vU3R|)Vu2fEYBNW7kxKYn|k{v~` z*qH=N0#zj6)&Vg;jS}0r_@^if!Z+aa&NjC!u!7v_~0=__V$7D@5&z zXmPD>@jV@B4kExqslUv@;J=uIOTWy)1?mij`Q{3g(@w2g@||A5C#5m2#C3oZ-FBAZbwa?npaR=H^w3UE-#&nzx}$;xyOsICwL1-{g)&0*b%}=0Pu% z=nBXcU8>kxG-lpRsmLN5qDbom%^<2-r<(^fD=0@SsO+d(W>yG#^NPxLCgtE`nG(#L zg@@Fza#E*MwA|4Q71iyC?2EK);S3FvNhn2Cku5p2A26a%AP#BoW0@7!b4Sk!RbnOO z{-`LNg6Y=3u=@!RY9Z7p^0l=w>-ODvP_vKp7pz?UNj`f2F@upMSg_7Qq0Ue`cGyco zg;@Z$RspP5*-%_4fh9qf`x(5^KRc;Cy_S}`>^u@DRdhbq^ScTON#{)<{XmK~d2z`> z-eRGb1wwg`Lubi+bm?%J^Sg-k$VJB;9kwZ|r2=!&4mR|Gd!FG5GQ_U#Rr-^3wv?oz z+C*_6ok3z35*H)$91Spuoi;F~h9w!p5jZ>^spYPyHT3B3HUIPX9;yh*p z{LTRUB~qqzNQ)US77UY}*yad*2Sfv+eaF)uY6a;n*sn;cVrk*U5-}_iM}9$eZ%p_N z5VZ?=m$R|m2h5&(?X$1TT9Ed9WZIK)RS)QjB8y%)I!6k<$UU5ZP7Nb-{~s6v=y4fv zaOD{0+C3i4Bl1)2OJjP=p@k!f^2aJp*;@omOZa`A#URL1U3NMtb5$-0Y7-n|M0EUp zB%5HGWslPE%$9qjmd0iRakUx8$u_;Dw7Oy9Gxc@}L+r9Og$>Ca;@#MHr*uohjz+9) zB`NTSWdc%ngs1oaVkI^Rc~%;KbdXdn1@t~#?Tl43+j{W67V5*$n$b>1y+!*JhkO|g zCp~+<&v<1$N^6U2%#d=fBo+dYI^|mrES7@FBynEZU~?mF@^I5!j_lz~E=kh<0PR_k zu&38v^!lVqr z8R%a)SnL-|Qv>Rgv;pGy$Hq67p}k$_d)`nV!u-*Yb+o;O2@fDOi-j;Wp0oHcq-?&~ z)QYy3+Fi{**QUbF+A9oV*YGgM!CK((zht_NsVKPZcX^mGr@~bNzmUZ<>ynDA-VOU6 zN_N8vm*mC5pv@QxGte?4^?94?wl}9va`*ux%0kzFyMZ0kO8hA8@hhcl1Zk8Ny2?Zi zM$D=5c)GCW0VtQe!*PgX5o?W5@o*}sL6Et5>E&FK1r^8&*EhVVX%8hBYOLG+bOv3bU@&8Ks(l!9$*NQ9Tv_w8n)r1#6gbJptV44Zm+vYDB6%ib)*B$D& zQ~1$|BC73IiK`CeD0}PNjgzQpQ5Y`ymC=8phSoPbSvw=KtqgDB4-4=wjwKNrI^S{j zXr6Yb`gFEv&2i~6M`Z9~V*5*#l#e%h)vt zQ>)R<|6)PN0l%y(s@_eoJ3C%fP6QteKsbTi(e)oG&2Z{+afSz4O5;5fb6xv4p6LH$PWJx`W32`33+7BkhDTcJqE}SW znutm7%8>tAN9qAme+)F))14^7N3!Roi?Wf zxUBaJ#T`Qw^hBOS$c}zKS`#@rl~aA2mVjjWo&X7#AEayqHd*eq_HE?s(c$SHhvhw) z%hG^n$m9zmeP)<%1XvM!(Oa4uv=iWmyNfGiW<{IOq*~Ds68R3Mld|ofJiqA4WYG-q zkvn6(#quBdAceFia{j=*+6?&2;>b2+=uZQHzJA>#YT#&To zTpgJ3IA-`%E=#xG3U+`Ky?8&vyoj|PJU{iS(WK0zBy++_9KWR>B!4%HHUd>2WE;Xb zbeBVoc-Q5fd%KHaebzt8CLBS;!TMr1=6Auicjcvl8KPy9mtAN3{=@&f$xHrwfu0?) zr~U5bCach8-fdR8APS6dO6??3(h_A}GxOS@|yN=B2pb057i%Whlq9 zE0LivW6|1v3b+5}eODdyd5ckWs3%QaJ*!_m&rVCJU%vJF`i&eBWaVDKT#Bv3lN)WW z{w&(=@@Wz?cdKOCD@#>-Ob94d&9{$*f^GWYuyWehq^M2xEq4=XgNXV*Duimh5E-uC z@(Np>5|08RePsJF-IQt-UfM?kec{pxvnX6^Q6IR!zw!0r56+YF+u%^&^OuQV&;H^4 z{Sk=sx#(zXpNoMj=l?QcL0(VE!!swsO<#W`Rqpdya#crQ9f_~SP~Vd6AY$Ou_E zTKHvx!)d8@0<#AwbTK3xK&(}MxpA4AoL+CAwC%gF&=l;KXgq6yjM%^6?@a!TCN7O^*tGgOI{T9Hnt;b9`@FjHUE*@-;$7uOM)Bi19-GSD>=_$FwZpDtM(ic;U< zO0)C|nyD`%Z?x90DqEUqm2?=W77*hwT1kpCEg@qsWIBOt0&IPeRFKN8 z)Mt6uX!!_erS}r(V$Ol>A4>|LosB(bM__+mU{Qgm%727}f$*rR&w&7uV~YAJ0p)ZH zqw2uZ*YQE@rI|VL3L;?oJ02In8ZG7_TI;S|L6y@(B+T&WdunvK0h zwivsaLQ7>o8=Bxj9%b>-sYnS$w`GvE=G=_An2|_jp6 zO*RNZwGs#dR^d)Vo-vw+=IqJLDz4J-9&z^beWxcf9eRbY!Ge;(3Fef3v+a#~azhCdUQ=#}q zDQ}ZrhVxX438$9$zD5;UF`YZxS6pzcWWqrRXFt7~dlzgYwxDHA-TD8&f!&=MT5gr( z#F+uAdGFLc7s39TWgBY)RoX7$5eHYGhja{DFUjQ)vW_|=GRObbgRsX4h67|31@^Mh z-vEs(S8KEn{d&KD79X!w2wMe%j1kE>pD7Z=1U*F`_Hhf;vThJy+VAN}!BHihF+qLf zht>Xs9zboIy@$Q$qJ3Iy4okq^nfW)nv>Bnqq$TW}ihYw=7fs%})vnJ1-Q%A+^C@1P zC(;x)cH)RRB)npj55SfW@ejcVpwJReO}Yk>sDLunRhzHTP4K@hde&F~LMRO7nImw4 z649clVJ6C=g4y6&GAJUX9LEXR%x7V!0CT&LwSZERGNOTuHMRz-dkbQsHL|fR$n&bT zAlh9eN)R|%)}W4#x}4aL%3!IIV!Db_>_C^VP>B!l9Nb55ZW6a@QDNWNkPPe)wy*y_ zYMEun3QoS+rFs&tEky-X5&sZjF&c1yB(S zXuP1oMsgS2mpC8`{OhapWi|pX3Bh`@W^<0OuZUe)8pb@WQ4={#wjS&~tX6<=WuL!f zkIRGF)LZc?bu`J!$*(ezOMF|*p^cJlMwjrlOC}2Kt;y#-F4TO=8eXP(Ol(U6UeY%V!BU(#XFXE%>9{rhJ7t#nSMm0oopnwI zsz$2x>~WBol{m8+%7_>-YM}0;xY7Oj?|GUTYn($`P{MG;737+%XI(30b}}0zT27p) z?-m166fIpI%tFN#SJA@Y1)~Hte@EA1uhf==x570-jcy+{4+nKcR9TVnhq7?kpSD$g zB!V^D+__5@Ch(_Hv&q`T$t#9fq6z*6=nlO4w)t&Q z!{?`B7h3z9q(kUI+E_t!7{_>LGQe#Kq|DC&h5-Pb(Vlr)$KLvOL156Vl+wmCSL$%? zJaNn`{zWrXD*Gr=rfTbRE}BSV1jP`nyEH%EZI9FBOE{~=jiC%onGV8P{N$EIT5gM$)t-p3`?UEz9N4~A8l zKh5!Z2HD4HCwbczAvw4}?=S!L;_k!0I6+UP{*wk9f^ywBfpwZGwE#V1R+|sM3i#Q{ zJI6loD&Yd*$NpEiT)!6j(f+M@JmO^6@BP18E1-3IQIk+$%H_4#zCpT*$Hb7}SBxh>V!g9$m1L z<89A5Yy~5C%kuQeb}Q8Lz+31y0O8S}gmR9|(`(s#L3krfO1R~fWteRR#Ug{Z);W4h zVXC+X&oqOEP6#jP8cSAz+GgkYDtMG%x6{S40WhNXV&N)izI_9=#?YM>Mux$wbMbR6 zpM(y=r50$)((d4C$-tb4M@)DOs#H^X`sSN2Y|*>{Kn0HWi6B>l&81{`L3#F4-U6|dR+Pc z!TIYbj*b=plxN2lxnDYT0~i^Z#>S*h2{XCD(ig>J*)wEV`zxvpeKrsta95w%Bu`Fx zXm+sB{gjwtmjUp7#g^?J=eq#!fYb1M{ys!$!Hee5FIY_ez4WNGw}(Scu)76%L`{n1 zTYyxoS<@`Cn8E*3Ac9EcXLJIHt#KAMUCB)26Cw%S|KgXkdXfwEenB(o!CcklcmEJ2 zCMh7cov2VhWLa$@>uC4f(eYpK^oNma!~5-?N_`s}nn>yvD1Vg84jmIsG1KZ+3^?wa zOJC{08wm@@<`cS_GM9%02GbIRSlq8O!h(`Tv=lmr|BGJOD{3R0_mW#Mk{cJ7Gr)QF zLD8?I0xge!GO7MRZ+_B@4!uxk;^iRnsk{87?rYKI49BGr`q_E67_Ot6fL#oqb(ws& zdjn43DDALSjwvL(LXR0>dSB&wD-fDjd{sBlqEF^*Aa%;!xfGb-(q+N=%%^j2Fw9Nt zWh=^v&0_OaJ7Xj!|Lv$uRKni^8T@J|{}j|ZZ8J76lTPA0tuad2=k~Wmh<`h0o}tlg z#FdR0Vkp4z2=kUIVPb^6+|hE-KfBKEHvpMw{+@l_>^ucJBKeN#P&*REXrhvgnC^-@ zH-+Th)F5CnFms*HIx6%ggxmNgVPWH={ace}STo_E93!L8i-=H1rW8peoCe`$HyGpL zPEhxB=`_S~1tc+g8=*@RM-4%XN(@qFQF9s`or?VC{H=}j9*Dg3(L-Z(xbPL{)R5q= zalVgPb9ws9g%((`WSOG4gfn34f9Xg5carng{eQ-5{^ew6*Xx}rOnE5gOT^bT`+F2D zJhpf^KNP3=#SD+4(c~SD^CsEO3iHroHS)oRffZXuDUz>ZN@3p>#QT?t$Y;lzQ%7}0 zi3Z8(inPAAoxZFg?b0e8GtCRCWgfV(i?Tl#ORn*Hj;yKRdQE19GtyQw>T&#a!O+&; zCqmXfh+zNnASBO)bjb7M4Y5xiUcY_(yN`=JA@4rRMM2TIsb1RQ->X4;>G_6u*(6v~#_$G;VPR-IB{7AM0UNDb4z?wmacxw=}i8X2=YdXnp)zzd!2h~3uh%A8b!~XUQZoirzSt;g~^yB2Ujc)(L#2O7N6B6lnesrJ8C|^P%&#gxVgjF zboaOC1`GO1su!kBI}*mBwC^pqo8EU2f%%K!siyZyrbF3lB1el+SS6{o7cnmy=~?yp zC4PnH7xMiISO7+v5zf)3tOvE^m7S5ft&*lTht)JU(YC&-*U*k$N_8uR&iYS~-#77M?+VfO41cFk{sd#j^6a64&A9#o;+lHIuZn zJ^bz+vI<{qJO-r|6jSOGuVm={17lq_nOWy2%6eCplJ+qFQp-D;K}C;sGO~tpvNUVj z4R7jk5-!O^lENCgsxE4%%X(WCv&0!RCIIT{X)En3qSz)>mRn^JKnV$OUZEvpc2Loy zC?{i88}mo+yA`twE4G(tDp^1F~o6xCu z<|ii>4@ars41aa#FYo%AIo+Bi$HtQ>W*yagbX$ptj+H%>vdFDlD z0DM&s+hijukDf|?CNf!dZKHU!Py}tyScuz4`H>5@8P5$R)$9igx9qm$A?rzUd1Qmy zNNYm`D;hPOTn1n^-(tVtBD8#xUC(RgnSfnl2p+5x(b&WRrjk|UfqP5&M>Z7|8)1v4 zh@|JXh!uVmoDF#{>9`o?d+wOP$>4Fer{34|NTUPg8Zj8aur>khkRvfaH2Ph>kvfV;Xnls&4dHtUaa55wMB^fwU8w-|!H)t>&r!%-=kadlXv zO50e@2^Y+bPEk#>f5$?0axF8vVp+x<@+NY3EDbbXt5+JjR{^)u4*rVAlD|PU$7D3x zT6#uS)*Pvsn%Nbs)U=Kw&{06t+)t?}$sbZl9vx{Y0SB(())-ku)p9VGKkdqOqt%L* zn{7Ae!U=h}w3)OnI~zMj0233ANM|$G7(55v3daglx=4gNcOaUfkoGtt_@lWTccm(13_WyqQ^@8w;zCwpueEkNzcciy?Ajsa2sCsXwmmrpF&!xw z@`&*$>p$X|LRV#G#1wU=yU+cH^unEg^nD%RqWy3zAY8YrSbp7Qq z*Q?<|?Fsr_zVRj%+3vovO(Q*S64NunJ$!Q?9o!lBr_+kAo6#i|Y_}aXXifa!c9y;M z-vDQ>QgrS9>nIDSDhK1)flh*S;S2Ppjg%I+HlO z72paR?{5Vyy+R`1Md)L6E!p8Zv_nxct<<>ZoOVOF)u?2Yky2SrlC>Twl~*k*ua*e= zF$`Nut0L;Cf}9?nNL;Gx)dv0sVDXp-fy~C4-&L7$4$pDSn(M0Q7u6$=MnZ!SEizge zDM?_PlB+H|?JvIVq{(AYLf{l8z!k(-358nt29~Y@S%kldq8mW*YF^F;92xL^#H%Z0 zh`N;$&FhFcFCjABE=558rY}N(K$kNB;fb<5IyT0d;PqT=>lGp#dtD&f4u}j{$29%; z->&SAg0HRaUW0?#=N1V(ruNXa|K!>HCpl4z589imIOGD@*9|G8)4Uaq)*T9^#dLMV z?kNgSYf2GM%Lxh|%Xg*HBbFF5t&Wg=7w4$l2N75qz_bTu<_fyya22WU#aj_D%5^%6 z#L~zz6%Cxbw&*GkYv6Ff#Zn`4%z?NYJ+UC6^o8F53sCjfRw60&H*1*>U-d$q85k*< z!g2lm9TUYd)-6<@x?YojzS;tSB!Rs4EzMqd%`iYmW(Q^u3PYR+N7-u(PB;Dd;blP| zW!o}Sh?Xo9UNSS*=AxsmhlN$Dh>&El)!9&Bjyu1@>QEUVNXcmtT{eZQfg{wE_9aNw zCY0n|m=U;=A841@A6SxbQ){i>NK)A~1+Cs7q}%PgTr00L zEq0i3ExFIp)P<(5+H1@~S50^4f<1N&rl1KhYJ{M7MF((%V$$x%!yY~$8FPi;TM3PV zvDGr#D=mme@386UmDv5yf`b-j8}^hLM1uvNu2`>l9bAl_GefO~Cv+PHJLxb8VbYgI ziRjyJOd8$-l;rrA!uKO(CktibHiS%M-ng1~3gbmN?C&w+0Uw_+jMG;b~^b%a+%@A8t} z5w6#qnKB%2)Dl1i&8|^j*>;t{WhlXg2N)+=T(5sTBRNg{2x~M=uo6IY`@E0;VVHLJ+w*n{&KT_b1g|5NfriYZKu%trJ7QJNmo&ah?H_HQy7Q_N$4@Q1loI!5JHYnIU8ZRMwqLoAr9!G^F3Ow~NQltGUD{gjvqYjGE zZ_6L-#hiJa-UeSSj?-6IP~j#dSJM(JxToJcBX}q!)2d$|+sZggm~U0F93gvoYLj;~ zUy2eDe1f~HO-W0kWMssL1qMN#5gy;prXziaOBKXVehO^cYfrY{Qj;}_DrIWQxG%~98 zU5?G+4Fb_RnsN^S>l_ZXO7CjUQY%ua>&BewM$38xM&e~5Ohfu&j7(n)?9gmax>zf_ zGH`aOWZ%NLaH+&vp!@%G8N(zHjH@%jg88T=AnhRRT=PzRd1gn&L$s0y)Z*1#OEiY1 zy^BmF5V#W&?pY}d@av7KhfGy1SJ~}6a+D>k*qTSlP2=l5XkY()! zu2tcrD0|0R>J8c_-D(piH4*Dt*uFEUjEYXgiru028TxI!Nh7WMnRSFur0OWAPidKK zBzB@4E(2d<`_C{-nXmWB+P&x22Yze+nNqCVv1b^Kka=CW9afU6L;#uOFafcc0s@7s z!INW4aHk~J)2d%+Hh8@gZMKw@*&qeNp2^6 z8Y~dkh3Qc_rseLmp)3>5QFvdoUiNjQNr}3hSE#a@;paq_cn?tg=PO3<`Kz$iP|X*b zTQMfh)nb}TLtwsRfQoy8urbtB3hW`^ag&)(=Q15SL6C~#T)$w$2 zTetkG%P1R}&ssupKYiXA!Mkua-G0ORjr1bMF&qATF zDlcHMA6!`fM7pBcA1UgXG9j#yHum~;rh5{~8|7DG+Op=5RWbf>{78T#=0#*)c?sKC zsYros#f-x!IIzgB%(thAAodbK(A4>edaS$l?K`Ys%Ew)!#Jcl5{qn^&wxMyvc+ap4 zx28TO^}2$!CMZezG-r@ak%)Mi^p!N>!PR?_v0>#l><}f>=%$lI2j1{KO3m678e1~d ztMicdPYd+C&?v3qu}R&JRZsn|-FkhRFWC;TOcpv9v7vR-2_$pziD=w`8e5SO?W}~s zO>M2{oWB7u{H|veHp;RL85P&fU(5#1^N}gZu@*c>s9mS4Yct8srRXY+ly;C}yw6s} zUZ-b3w=?6cc*Ra;u`!)+i9e#U*QR6+Q^eEN@u$+F8ip%Ke~Sqv%Y7BeHfpbvGy8$T z+(-G95NHX1il1hiVGwYCqiQ^1{>ZYaquCjvqt*AY<5U5wpAi{?!WD?p=Jb~+xE~@5<%V?Rp!L)a zw)dEQ_!8fBM6uE?r`yV6;oUovsS8i2Z1urJ6wg2!LFDvXK- zRhM{q(m9|G0#!MV_|7%ata$25GTVi18>-80x`x|5$Ja)EBT zf)6Z5K&GfnU*G@*al#xMRcWY@UI76{14J+PH zkoi}94JN2S) z{FXe}!nIG=BW9v*Vesxl0>_|6YIQw&CF{7pZ)U@l) z+n{BCY*-eZtnZUMF219xq%X#Dq@;aJay6ltk;F+IeNJ)@j%bai^PQ6)XYx}W*d$GJ zH;g6IdlMK4$4}}p<%rPqhRKUkNs}ZTM@sK;un{6qwCRGmWkL zgT-p0*!FVc-}e-Tf=dEFQ@*jV_qa))@BRFV0b5B!ed_xR$#t1Yc+85tePyoS%( zIOW=M#9R2Jp1U#eF1w%$B@?lt{TCEiQ`T&lpSM`fQbDCVO^eSb*&#AJHm$EBVYP5+ zs@F5t+)vGf2EAM}t8*2#+f7lbJ!C#Tl6ub|tviw#4{=)@B2?#8BiPYeaE%y!B(Qe~V@lkN;z4QS28DR_c>V zMGqo$WcTSzQi&!^X&2sjw#Lo078?mKU>THTV#%_j$2g;5ZYoq3aqh?e;Nez(@9htm z4dZ<`+N0p!{K=UEo8VO(&yyl5!2;lG!|HWn7d_~h&jp%6hn?u*3z{!(CM`zSzN|x4 zwUboD4#qFKFvcV*q`pj&vr!5s56nK(BpPnur&=E$fPTJ`rOiVInT&%+K!R3m8f}8L zXbcZuaGWtWR;v=Loy;`_-QwE zOF-SlME)k9;HU35C7nI!#FWj^zkDn9I)__;igXxHh)@jB`6zU|C^j61F1Ae{ab zC*4X)C5uaB{;`C*qRCHj9H(P2r5hnfO%Oe32kso0u83m6V*x1 z23e{l(rD!*HW|=z{9Fwb!YtAO>67X##P5cQ-5#;$?S8qrcy6LDx+!u)UuE2$Wg zs-H|s(Y0cWy(8))uCf^u0j(vcQ`=3P*p3%*6%c92E2J~kkClit;|cl=@G4sub`Zio zmOeCgG&~ciWF$5LNKHa>8|%%tu+K1&G^!|`kc0BgJ#bl16cEg#etH)t%EW&XaFn-! z55=QnK8@T8)Y-K6YaUUCN-KW^RPamfLfIbq<>K2YxYu12=4Fa7p%qH}I!)Vu;4 zh{{M6ZM@d|UhGBpOibL~^;gTQzJ3x3-mf^`Kv%)xka4Xn7G8HRmeA<0qfRkdx+$8# z_eNFI3DHTZ5|ULfS+Ps^a;(HuI2O^dzAM%!8UVz2rQ?cAkKU$Zx}wW4S$3?QcE(PZ zH#2X1n$!Gzn6~!Kh+sRaTp%<9kei;dG_v*Z(5$TV6kf-tSQc*FRor}KT994~ADCVd zK_Fc|t-o{7`_K95#laAPu!iSM2e7{-OJ^Jp_0Ja(?Q}V z2G1lETx0=Xbe0446C+EX*TAG#RH^fA!tK8?n=)hIQ91b^yPfoP;bk6{o!<0jJjQfT z27Sr+Or(geh>g+Z9cn)lrMMofZB_Qt;;EqM(WIx4Pr7}rn47uDobU`0r~v;4Guu(b zUVfx(-lN5n*OU~KwAn%XL0uSsU@%D0-vzFq2o_n=HmJv;PBbLdh~m+p>yYi^H95dQ zSVYajc+9b0uKvmxUMtpE+)ZCgvr&vZqs% z8hlD^Mxn*tYjhFC%2IozqUQkyA-=C4p_6Z$9+_uoQ3Xw+cSz#rd(ki+&1JVRTX982 z0P<@5h0>8Jb$iuH^3f+&WeR2zf?Sq`JYO*%eGt&TGXs@gGO`@H5_US5+d|@Cqx&`* zKiHsdi-FMc04>=C1C2wcYzn)%mT~sXNpDfTbdDiJ0Zx!YjT|aD({6AilPkIGGUrVV zM3-St5?n(n@s{?8gu53*KV$2GvpDs;QGZv1=6mdto$0jixJ6!brt$`@=D2eFXmH%r zWNkToXJR6b`Og2r-h0Nw`L_MOqehEfGejRoucL+Nb=1*&83dyfNsu6Vi*6W19Y#p> znuyM5i5k5m2!bSnXpuGlyFcr>@B7(nm$g4@ul>pk=XK3>o}a6n$8r3A--CQV>IYmd z*ysh%$iY?GRFH`e{D%vd7t^#12e;E7fXo}}h!6=cL&buT^OlcpjedS^!ouy{$U|r# zCE~kMwiyi6oGsl%v0LyBSUL;0c(+T&VZ7otL5z=kYvxv0@MVv^U_#{@t|szxV1+Q< z6O?v6TBN!xPuH1CEPn&gi7?l5#G<2)OH0c8d-?mx;pB8)sFJSlZ{JG08NU7C%Iy(q zHo^K%IpBZ@s{BE7lYlx_Y(>MUGaSXg62FOX0E;@$I!l?2F5j|%A%NoQL3qkaLMK-X zQ(3>%%!k()&68p^J9YB1q||%<#$-jKBL>~IMb#m7f*3T0PKk;3>()sVWW^x~N1XKmm3+us& zj&014DXUm%P2@VMzh>1mE1n4d>@AlF-ho?XP(Q-9GEwEt+v1SC`GzK1Ja}OB9@UmXE$by2ao2>)6gKt+b#DL za7?kP=caBH{H^kwao~ksC$XOdcX0y5V2U@SrpsT&1)|*h374tPTaHa^xDRf?Na=zi zZ#<-Rrk5A`v<%xIDYKlqx!RFEIyb8D2(BItCDc{;6&0d++jM%+_hI6BJxm{tO}da^ z>U097$Zhn`dW5!Hv5M1`XGU$n_%itcNSRk&i-Nk3tGpz&CvpfHoGM$Z{J&KysKz4#xBm7wpXZQAB3 z6H-N#bo4lNeb%ycM(0l+D`3?t7!ymAXDz%am)hL%%b(l}JSBKVHze!7juZ+F-cR(~ z4jk)(Z?3Sk7z$^AIm^H zzjvd9n)N0oK;?oYQNK&S9>!wi&ML*HJgYaL{_@PH!^}<7~J%#pM0#H+=z)?(1{u~f- z$;Rfi)&zAk^`<T7g>Jpfp&rom6}F2y3(4tmlo@}voou3UCpX_`<@OrO|6GvEh2z>X4-M~vJPkxoeHQ8>=dvT@G0+VJPrXX|B<^Q<&z=u7ooRERi6byazg*@qpIW)c;RPFb!yVEY|uTKu0Xrcat? z<*lc|7_3LrwLhv%*<^Jn(ENNIone&x6j0fuJ0Gz|vMXXR?@b6FNvXIcDHzo$pre-o zCToAhAVjp&_h8YfbN58pz+knUQO6yTX}KF)h)u@lBsFBJ+)Of;eJX71Wd7dHIRz!k{{+*v=CfgJrm0r3)J+|@degkyV1GIjXE`Af7Zv2_d zK(WOg^@;qlxGrvpNFhJ6al!B2h&)%f;}<;Bl`Co!!`;nnwv$`nxSuzN{%une>3bfg z-`fQI44ESd$-}>|+&f9MYcNck97fW-RgL)-LEwC(Jx`{RxHF2U)Pk*3pKUxUlJ!gxwSS_JB-~=<0xV-MEhLsC7ifS$#LHCE)8ojxq7OSV--8kiZmr>3kfEqtc8l{tRRg@dI*UqMC`ALZ419LKnE1UgTpMx?g;QLHdZ&P!B$c;+lA zys?bin>(DwV*13sKd|GY`Rj3yXtcX{rP zOlIf=1PbX>iJ`1EfjQJeC}mqI^+QzJzHx&jX)lJ${qnvoI9p60hK_*>ULUP294!xw zU*y3GsFh=^d0_NCPWeS4<=HuF1CyOjJmC$|drclky8I90mUPpLKe2aTTvH;){H zDHR6V=7j*a!maI3TMDq|XciGyRO3D3j`km}B6#y%g_j<$3DX=77`5!U+mCCU8(bkm zcm-msJkR@>YuS{Dda+MY1Y;(mcjuI5> z8d$57*)tChElfTsP|f%abNJX2%twKi&`x=H*`n!-9dF^gLP8fT{<$^Y8^@5}C@&}ztspljv1Uye4wH>DbkAkMMQ{4>A zaN9{*Oeg1?H!_F4WHZ4Osn2zcd-IAqxd6qd;_>!;rfQE}+R^FhWl}y{z&s6TU_{V^ zx&$GGo|RNr13@xtnB@3X-dGP$_Pa7a7ki+vRK8wCRSm{SeYD23$L!|&v{HGfLJwv6 z(PB{%a{PUlRW%h%et5}%3$QFqiP9FZe*9pIvH&HMPy-KtPp|ntF__KJ5Vpt91ik%6 z9}l)T$ob%jr9z$_eJ)LVj`vl0h2Zo$9fQ<(my3<`D_Y%5)bSUI&S9RQ^WwZC$}A3` z7ir@ow@{}s#duxI!5XyvSZZ}VO^4x>e4J5aU>X@gm5 z1-93-EP-(NkJ+u-u>`2C4mH3Z?2n_XejyALF|;ztv?_YCd4LAMa zSANf3R7HkPE_p)(?*-!FFp@!WGMTf872(lfny)%ov3O_7?Z~8LZ1SUQUAz-42nIO0 zR7|>vNA?o&d;B4BTu~km?z;ftB#vHzWt~84BzjrFGLU*gzw#LV=9+o=X?}3zTT=jz zMFW|I!9;dl+~sVTWUte%kQ6C*#y@s`4%zKh>~lNA|1Y{nB?>j{hO#`=_ZQ z2l*!-sQ;oa^G}{mjP?Uy9SA~J~wx@~t-j}+yJsEa%tu_;CnGj;aXNA4(0yv(nXFhyATPEjU8)+t@MqTtiv$Us%5WAH&JHe4uJaqzrwDnD<)?liYc?!>Nh&B$f(Q)f;qd+(Km=EBTKB z!f?io0!4p03Cdib{R7g8B5viwnF9D8b=OmguC%-BZ~2$YJZvmmAJHaq;*tp zY>-($U-MvpUwlw(s5Pl{29z2pM$;nkmC8~%FyfS04(W-BT^NWuGt9&lO>W%(F5oMN zB+zhR2Yr~D2*Wh`W)ZJYd&Ko|=J81gx&{a`$4E!4L{h&yi1ju7FE+<$slg&gL8@a6 z6VH=H;aB+03U?p$=<{+%ZQ)<<2yuQNI$}!Y+t+)o0U5TbjlO&v1u3-CEhOqIqZi40 zdhGrwDl4;mYxLQ%F9EOb1lv2DGKL6dMdwaH?L)Bgxf(rnWfQIwn8EEWJ0NNEDUtmi zsTewP%9LQfnheNr*?w7H|GK?6%l(BJv?X1ww9UCK&QXM&0#W_OSkzs1TLBy@7eF~p zL=s8QQLqix&;Pl0-GpfU*)YjC%&qgZ-kGNC(;Uuu>qAj8j0?zISkVp8f( z6dGV#l@r!%n}hcR)UiMi7g`++{OLO5HXT{4!HGxsf;1PPF7?5p>#v&AL&Bz+dl8-us+ zQ4Da7(2>OocsP%so&?>}T1<&3cXj^a=P6;peVc$=on>muhlOCQlu;42~ly5cQUe2Ba4s7Ux@vMM7^`bx|sn7cRp!k zO7-uxD@E`F0IBKIh#vo#Q@vMfJlCBM-q$9s;BR>Idxu#OMg+#M>BQl9^r6Bs`C>UZ zE9H^^(c9*5F=xG&s}tXA?4JZ;AMu`YYr%kKoa0&gG`2bi1tECfl);v!D1E#Ma8+G3 z?`fvUr%zEuZsom?TFzL{rG5k8?botc?3Tp2N5~NvPd&VT?c^5wkJm>R{Wa!xnp;G8 zdRdBHviJJq7|1dlktAQ2{%RzA?!4~howf^&Bt-Hws(5Pn$Qv*MlMxl*d_-%bs(yK+ zzvFx3Dg$DP(3h#}GOSB;2?tWvad4}#DLW3I(tf0Zz&JFG3Mz8e2J}gmcY0&eo4r8m z&Vk)xllK+|Pv^Qf=PD`K5(LTmTM~+rLa_oh=%9FH^qpTdZTceWP{;~D7e0iwFS_hG zq+n8jsUlB*TXa0izSlO^Zgiu02&B9Uc;{cIvKu0iSek}uP;dfC=HwBvR&)hL6Ap-l z_*T}^B_I-?Ezq_I5+yHu!rW;TiV|chHKa+l)ugQVr6nth&FZ8`4uCUYITU06^ zPRg>Hu-c^D<(Ps;Q#j|Zt__PD>u#C8d1#`)<(mcHt!a+5FcR~y5Z@@1?W636_b4CN=asVVT1-9Kpkj)SdE(rO~JNlJJrC-^mC1v3DYLn&K11!$jKy%>?BQ|u;iDzUwq5~bD(x!?Ke6G1=4}gg%U` zU(^Tls?mnq*@Ul+g3ML~Tp8@jvLfNhe2~B(Em1$NlaDb=ZjHo-gf4MY|Qo7;w(f^M(PCFP{BSEX>I47Sa) zKEqg{4N5#H;y1=c12TgZnn5SInFoOhaR7H_GFh+03uJmm?u~P~JMRzbg($_A)nxC< z*gW9W-OGMeeX*)JJYenxe%^jVwKH^nP{Ru^lNP6rxwQ01XoyCQe<(<+%&yCAVJK8= zS6+&`59kSvSKIT~;kDA68J1ac5HAjJ*me7?D zZ=?hbE-Vs=zFs%{l#&3B-d#W(l~`rEv?y$43EcdSrzWS(nfTEm>G5~n=rfN7{RUaH zZA(_VULIK4&~t_^A#t07V_=(^M0J^;k*Lc@kl+5ira)|f>9nf7uzn7giZi_*i2L%p zRrLXi&o^K|J0P0CigN&^^zHK*w>u9!4wi?Rr|y-Dhzg8Y`oWQ$26G_}${&zR-Pp+C z+C}jzlszvY0Bpa-?E^L|j>og!Z^_4d=Xkk5H~W#q1efNNo8%Ag)JE6RG>=3nL+w|Z zE-LX(jkB1!5*W}{xqX%il+)@EkFBm8 zbbQ}oW=8(N^ygh6`pnosmRp_MEmmTOxxtrp1fW7aG(jbqXRO%iXt^A=>9g~Anp-Gq zpo+2G7va*(Id|C6aKb^R*eNm4ym{6^YJv8ZkBWZjmr~7x`G{>AjdmGcv9HOux=OwT z?|8=CuW-BGC;85V$t~${qn+w$jIta^}^7a!1_ap-0sf zxyF<6F3j^ka)X@2KCgb!Aduc}m3$Z{B{WK`25za{7mXLYeE2b<_Pn-PF0SP_AQLX` zUDNPD{*FrQV$jWxPmB=04P?h+`esX#jEQ=%M^QTTS z_U%C4+AJ$qawj>x_h|&ui7cfBWtE*=(JOMMOciEsNA<>43}fF0gf&krCnTK8?@?u!Wv-!xOBV?<`PP zfrj$4@5>+>2`GW|=ziH6-hGGKo8>4DM8n6*@*Wd`P9AtwlfoD=0X@AXh1^RV1jil} zbevJ~L;(P^O&T?h^~Hdv0nPgG1%K_P-~y6(4kHZ zzw|8scqoj^GE|ZJGnd+rA;R9cGy*$PG50JCTx*DpqKJ(-K@2`{Wg$B@CQI+P3~X9; z_9L`u+44xCjhT`kjzMGgYtsY*4p6;CO8&HowbA^MZS7h8Jb5nS4v?8NA>l67Ce`_C zM6k+q2}h>E3eWB?pD#1bRKrnLdk;n*#Zvpc9!NLh-pL{R(ygiq$pS?zwJtis^_>@R zH-7VvQ~B?WQxPUx#MP#RA^pO?0pf|*{T$91(1S*g9T#T?bdbcilYaWZU4*4N39R7C6a=qL2+^%3=)j2p z!Y5Nn#qP|<6+$T~la2V>@dWJioFf3v(@0JnOCuTzcAEoG^z5pqJe|#Bu26YI5id^n zwXJy!Z=nZB-RKkaOj^_W%yvmf8~!Zf#=7iJM;BMB-+<+Z>2>H4uM69REvc+jAI^Cn zat>c#8mQ&GW~dD4R#d26b5Ykm3&PptCuxK*MWOzLCbW`%aMHPcaKNmGsUN&{RQqOu z^0hvAtO~4%5?LsJg9)tOg0|mu&RwL+d__CwId7`d;c;ulkN>ZVJ@vf;B9cRNVa3>j z7rswUK=6&5BldL;hW0&gfi(LnT-MLiOmVeWzw-0`H!=pmNb(E`Z{_m{{RsajrlBl5 z=e8d^?c4K9c!J3J?^kg)NBeLT(JSMh);E5hV0&^PCUqGITamNM@;JZw+UCCIHezBOveMd)bilxNg+vOy5yOf8`t$1Zw1u zi*MFBpPCO0{U^dn;EVg8*efdb=>INxt%g?ajqm07+OZm-KltV8Eic=@UksXfXr}0w z#*8N;q6;6~K&%r|zE(m?h8j%|28TCfy_wUO{#r?+eq()-IBle2H^Vw~OE-Mge!~f; z)Lh@>?#O1*$sWCBYw;W#y*gVT7LuTkGe_ET%-S2GPXS# zy`nK&AmX%U^pW8CVw1t%_DeTi=<_VydU`nxiDl&w&e-drR}43$R*v^A$C8O{w~g{t zmyWcEx;Ud+-OWE70Ar&-S26q{fONs_1T;UCC97QJh-}@@i0X^YT?chVWV4B@WPvP& zz?-lZGZ&`Xut{-Wet!u+ErBh=7D||9D6{VErzgm_7`VP|%7=T{RYHb+QomH6emy>k zjPVNc7CCxs>876$FYxfYZAfdhBI$uZ;sMR!~%N-)F>Oxs-DO|So#<;HUOwi z8j4R{lW6(g6kdCD?my_xL{6!+?R784gnO?LjC*X0Y%ShmlNHmNuN4MlQBM_fO9Z7C z(KEUxacW2(2e%RIj_c(*EMDw&l^o-BHp1k7mtgJUpRT?7=;V#eWGwiJp7J&j2~%jk(#kM;L$8G z5>&c4FqCxroBL}iG~W?prjB4hS{0}mMa!((&0}(w2pRVS_6=pdQA)b;C6>XK&5X%% z;Hsb$Enc@x@uB5jxLn?pN1)2^3KrF2*Cu>96aKNIlJ_^@k+KoL1e8dE zu`h9*w=QB$vG0x!CN~Sqlr=gdUlU;`n(gC4$?fED8z%c3U{gDnAW66jx8W7_bJsUW zipj7{%%4vcq+bstnQ!gqE|#BEddTC{R4}$e{&{eu;M_G%r&Sel8r4I!m38&@oI;yEX@l*!vB1j!9al!Axv2#sZcU_*m1&mKbr6(s@zI4|Aul$ zb@lpgXr$?2-|{hCky+L*I#ZSF=17&IUv?%QO>?H4+5!c|6tWyypZ8VPScAzFwUk-y zLK>RZJqu5f%O6+Q=%}z#H`Bd9l)8ay=U>AreD#XQrYfL~bgg!#S=!qzoZ>i6;#bEm zabREmu6#JpUhu1ITSgdJD+rH{HwnZYtu7k(m|Qm7ct7nCEKe10)=WKJY?qcNkd*Yi znEG`?R_<*JQDb9E<0Y~x6XX*fN~d17h`PW(g{Y4O{<~&Q1$!%PL%SZ2VsI@Ke>fX1 zVjh;9P5d2u_0KpW{g?J0BCg_UM;6+Y?5xcDlMlIZ6);S|HTKnaYl`jU>V}d^JX6U) zRC__$3UiOy^d~V-JAvw0_DIv8?6_#-ekLy3_=Ko-S`m4&5+RizD1uBa09P|VT@pz< zaT1RPa11;&k}&hTPH5Z0X*qp;_Prmu6$Bg@kEyjwzf@XpecN|C2bKRY;g9{ILfLM5 zOLcXjyCAUaZyUzfF^$cC-Z0`d-tglnhgNVBhyjQlPYS8dS09Eu|7TR!_i&brwKLn} z>3op(f>03!Z%cu#!+)X@%eVT7Us&6h7~G${n$Iq;#Wj6WZH1!o{A~N8xovpv@YL64 z+@`gh!%~q7dBNkNbEF&8di8ECaBlFXAkw~N47O-L&~f?y=s@%+2sOIxrmqpBtf34c zj|}SjgPZoxZlD1-soo-|9QIvfiu7yR#b5IbyCacH3WExPKGXIoHAO2Lhj-xdAIFv04sd+C?Tv#X5cU19h>)m4m^3-(X{ zSywpQ>HlnM>V$Z|QX?>udy7s&tJgU>X!j?HC`dl&GMXuqO+LJr9GhCGv_Z5vWboWC z>d2+iuubKm_;lqm$7|&7^dYr9^nca?Jf7HRV&VmCCYT(fo5kd1V!<07XzS4Uegdk> z+}gwc7q9GJEtX>(O`#A#rq>v?mX+W9>L(!~9$tH1<>c z*L*5Qp9FYanLm{+6R4>VS{Fe3xP(Y%g_bc3j685?7RfeKqw1~>eU?L}(`c2PV)vbP z3r4vcc)jn+ONT*p3;Pq!QfT0EP8-r%&f)(34*w7*QptwS6S2^pk@O{Xck z0gQl?**|{)(v5XA^jq|hCE=gck#YQ4-3tm4U)`<({yF;kFCWRrTz}tY|5K>%Y3&F~Q6))B1rb>9i%D!BZe%~M@ro`p|9x9 z8HYVax5t6ZPeqC#V4CfO8`}I4%<6Geo@@LU3CY(*&g4|bRk7N?0i@oK_w~@Uxv#Qy zdV7)O&2hwD+hW$d(=7GdbTQfLi3t>8`A&XaQJ>E~5f&MXYt!|vfU$4S%?;M^6(R)D_L=ihzFxE4I=a1J<*bS_idkc43 zY^rr=Fauy+iD2~^`UAxCLpqV-;M(PcsH2QAhl$%HEc@8Yr?U6IscA~z*d%}S5A4V< z7k?^P4*Z=UDSvIyY4xS`<_vw71Sz#nyi{ypbg)F#S8zD||NrxUdI>;z$eDP09MLcF zz9<~=_@TY~9i3Hjm%e>p9MgJ<>cG0lG`eQEtUecQik~Cnz8>#vinMxOy zv)Je1LY|xNx^kog+}HGOwM%}jNU_cPIW_nadb#Uj0SZ6Z$MpLWuh#~}h1S0Uv>F8aEV~>xy`?c;U3&Gc)Z9haHCC+E;8U9D zW}LJ9Gr{$(kEvxNXL1k9s*buS?fLiayn33O_`l3Q@Us9F6y11l{(6r>q+NKlK-=Rh zmUqhm%g=%&A0xyZF@Q#fCt318`+P(2dzMdr{j0!pCjO$daD+!FIV{io(Pn&_VI?Iu z3DFNqpMGx9tPiG$$&07XT&r%0iL9YS1h(OfwAf}9p6szg5{4Hcl*9R{>Y8($P#H+r zLdn3L#o`Rv=jFDZ_1vW_y&7Ng6g~nb*s1P(Eb=zeVKtl*k+w{qq}bp(87uq_aHoo! zaoxW?wza?3NyktvP-9X!9AT>>ks4?zzx;jEHD519K|sNA>}X&#TX5;Np#gCFE#}|% z@c46d>=0k|)%(MlvA_ZR>iyN9VRR=erX73|UbNPm17aThn<|v}U*bYfV(d@|T z0Qgmy)4Bi4#|D?$AMWynmwP?W?3$8(hh6iy^?CDaQ%c}b$f9QZxxxXr?N#Av`v3X^ z)dUck1d0NV0fovSLjn95(;Xj0zcWSExT~*sy6Oe#+9i#M@Sw^zCubWdfNV7h+Vs2i zht|KcnlVN`?tt_P(piMT4rP&1X&M96LL^MZYdh}v7b#!GJ4*#|n%t`7%Dg2zTNRhQ z-e_or=x6to7>|uREk1|$PMXm0El0Wj>m24Rs1L9N_!)R+fFf`7QV;FIw z<#CRW&*)`@cwY`!R`c&$U)-NFk4kwb4)4Io_+}s1b2zt~e?e(kLyQ-QD^(M>)pW|= ze_d|%tdyc`r!b~Pm&7ixLHIwnbt7U^r0eHlrAzs|SuF0rFzbzh=?;4sWvJ7~l=$by zwD(~-vznG9Nl8&LO3*g)c;bQjahIEMVib_ev&-enPyL8j5)CNp56c@PK26rYknZ&_ zhfEgesxv(T^}n>2JZrWrNg^Sp|EVdPdeRr#E!dARGnaGQ1@w4YNQlh_!ayhX z2@h`q!p6=PsF){RGLcZ3NpIV(QH^>q;h(c^rv6A1#RS#o%gBG^YNk)ik56%ndJxy= z4zP*`Bs%1tBdK(^;T(l121D;WN@60+CXZ@&c9pudN0P04^U|8Uz5;(W&09*>mQIGU zQqxpBfV6I1Luwzy_8qt=m@qMX{JM%Mvz3WoHd};i@t!Rg1Z)^gM-2pg{L)`k=gl+U zTb?1$@& zX(ZYV-#`p%;P?iWeMbfyMEX*^0a-es!d+9Y86uJ&Gh;@Om5|Ea%G!(1p-^Da+&I83 zTV;*q^I4Y3t*=}V8%!@COQ5IY8kCK9nd0I^Nl9Q@)Ux-Vh?NZlrG=0A`&rPg%hg2{ zFQMPL8>4QE~hbh=VAj)u6V8?a4Mm=Wd^5Z zdSVEURF7V&;Ua!7*X_e{d{OwPG~Q1C&*QuQvXFL`n0mVMB!>3ooFR_d`e!z>-Ry6` zf=}1INgNd!ww-b1aQ$TFug_!qm`R+Q2tGdRU#!3t^_$}t?Zm=+bL2IlBJlKlYV`V+e7PBm7GFU{&JZs+$HiLw{THT*)_z_0L0L6BNlGeUf z?zNmZ{HlEDE+OTa^YL{zwH&p;94nZ92+;54Ow*G5VVdFV6=d`?w>z1qofA^N%56(o z6rqbZ;+*p<9YEr^7^=*V#>O`bQ1YnG&foDnCP#4GlF@wk_+5a~7B&=2>Jdb;yU<=h z<_baP(IRz{9`|xTfB(>arax#gu>c$2KTTWeN(bMSB#M7YO~cPjAa?Srq$#$k0&jXm zL_@%?9j%%$tutK_2%ql9OYD|;dsX@t*N$?#=%HgGw!na8^t^PrF=pNY!7bXh1y!Ng z*bmK(4fKx3JcZJ_h~L}ukkh$A%*_Kht8TBe-AM^z`ert75{EwDwV57)+qCLU?zWLm+}IA;R}Q{)et$P$1FxhCgOee8=%e5KrW7UHzBl=eVn0b%t#f_yUePK z&&$6g_WdT(w5hJsUqct}GhcL%zaT+2pp7)Z!x=CTP5kpWAd9p9AV{a6x-E<4{$?(L zH1uIEni-pjPehBniJSjf*`a%Z!KN-uQic*lR^7d~MX`ABgMP3+aB*p&NprXgaXzk- zVo)%H#qxeZ@2a219ov}k{9x9<4oVK6%HonR11~1@*mb#b_3V~=!esy^u};k+EUkn5 z^t+~JFP5jt^cYZjCfa8+VA}3#4n_(!r`vH4xXgr$PZe}qF>E6Fp(?cU>f_qnoyIOe zaX{ho^8p9B7Xu!Oe0Osi7X$IsKdZmsvc->2P)0z=uh7w(e+Am@z-9^3lH8zG- znRW3S5}#?!llumLe8RPGQ!Z?w%!S%@dT@a2&Lqb!5j6ox+Qxy+7L!Tb>{F9Y6=>o% zu2oZM!o`qfH2vrb>!hI~e5>qpARmdh({NP-pC_M)v9iR&4!kz^cPOzw@MfN?tsW~N zkGqhr97MiUEQ|M4^GxOb-SSgqX*xmSJ9KI!x~R@Uw8M?#$nbA#s|lglx$%*ATRK(5 zcDbvcOz-zR;luSOIqij5U4G05y`Z5 z+TQt(r<7((18%b7VVhgQF{4gzRhHxM*W}M`+~{bz$G#~5Vhbpq*JO#&5MR1?nJ81D8T&hy7g`>N_)KeIVV z+G<(d5N}m^T6T5z$J*aqnIY0h3Z{xcE|qflPkWE)u@@ApyPXh)UC$l|Tde_HznHk%@r?E9ld)qs?@SSo8 zOX>73eAtrP)h@Xj{Kc~uF_>rVE0kY6Pi<37jnAJK=-h^bV4Y)Hnm%^k%+K;0TL-^( z+u7qMrWtXq!$j+cS)?Sw4fu`{^Q1iIoS(J`xTs^vs!8zl-+IMA0?cL9=&M7c(h2hB z#q?LDPCuwbLKoGEf5khVhBjJfvsOs1+;<4AHCn>+W>Nht8lbe>UZ^8%9msdN9h6uz zjLBfK{6p<0X|@mLyaHm{0FzqLw2Rr}uu%`5>pd*=;#No|9gC$;=-=tFL{8 zl1lgO$pPvPui@Pq-kq`J65}xqiUb3BGS}{QiDxbMG;LspDC|nrf>tzRH}kg zmmj(Pr#Do*GtH`5z0Q&T)yq58QN<1;-56aimOk0wzW4U#+fDAdI<|?4G#x`Kk|!|% zX)vnAgj+u_qi)`4z3fh21W4Z{!Jl})m;=wTi?i;&le~|PnM{bB5e0uaoB_%Tc(PTn zg^wwIM8oV2##GZU=re#!Yo~px_Z+Xv7`TwSZ0RYPyeaOrl~P`s4O?4zw3X5A>M#8X zBAlg%Udol?TKOoCNV(_5tF>Yp|twsDHm=cbAeTid`R39=tW44)qvvNiGspPGk?lhlWjAy3O`~(sHBF%1t^68W zef4?exgIpm@KU<3)?zyLIbYy3m^!*D82~t-CUk2=33<(>YLck}9m5rjkGFLl3jnQ@b>{cT` zr%W#Kaa58Pr<0YtOJ&;>uwUhI$lL$?eXouNh-+!9HG5dUg;(QcjF45j@SqZJ)~9CT zJHu?+=@?w$NGRx?I??f<@AsQHe4phKQi+)Drk4nI(hX$%7nD> zSvR|gsAK6FRhDx!-(%U*>R_N3l9lg~vB1No&%j-_Gk1QL*L#n^&evvQHUb+qNUi%` zM8`{-@oecW{X-}h!EFOQngA9dw89dlkj4H|{fe>g>dYdBb z1d$g?1cAovBZ54pA6b`{u$!8N2Kf4_m! zEInYjMmWd+q*O{PN8s2Vj2#!wG#Yxk*mlcGsT`hsN0xXSQUqHMbxPz6BI6#5Kz%iM zgWQoLV!32~3d5R{^{6n)P-yG7V>8WaeDsLV}^gn5=0lX+UoB%v2WJ{<<+ zVYNwhmUTho()>)6^vUytCEojU;|!ChB9;87nF|5J^ZJ#rW?OJho3j9aY2H&3qQ+FO zMWx-DO3LyHG{?%zd6ob-{k9j)vt6{vLEy=c-Pd>VrIm|oQXM-`MJZ5SpSZ?$(QfKV z`dg(LVSTx6bvKS<J0`8!ysTV06loBfLJ_&KizU@zNTZ_Y?Ap z=>d4$SzFlkFTR8b)xDrpd$=wKE0CXMxXX{`^rvRxn}z&RcOJBn995hg6xS9q{I%Sx zxo4ep$g^}y-u+pMqBI)MFgMEam*U)6^}%(eL3#;b@|gRnha`E5@2fb_tPlI4ilIZx zL)@YAxibQgY8JFsieUn8=E{1n!bTiP2v;1_J({o>smADtMY3W6N4!IOi2MSBs9w(4 zE9iJ!=zZBVvFpdb0nI>eL`|KG(43KJNRcQ%VT(Hsm_g~C?|r*F(*2kCpDaZd9(g2R5~t!T#u7iRTz!svC=(A zk~Y!NcS6Z5FaFSk9wGuFG`t}7e0G`Bxkcee1L%rXq|+PFpuV$VOv4iu&LqDsk4 zl#Ux59k|u^$@OE3)Axq&n*TQqB;l3|n}cV#k5DuC8Ta}|{Xg_G|HXxe@66K0I9N%O zHMof}1N>a@@IF&}-Oc3_SCQNzfid?)uk=LUYUKb$!3l>Qu>AKT4RZFk~d05Y{77${U?C=f%h(8#YZ)0ek0dmz+`me_nk z#J9-+=B-ONBy(MG0;mNhu7`}{f<3^}itoaq8f*2z)pA%1HLHLB2=^>5&P@qlXwcg; zDj^Ct^|R9c>ak0vgC@OWZLK>$X7a&8f-eI|0U8cN!B-fs`{;*=4u+a5k(b-hO0kVR zq$2h~la2plhbo1TG?WMd`W63o5+2A5vD;vqKfA|P3$;1D2zRW)wu#?oYVr8-8 zdxnA4s#2Q{=ewP1FJ_>ShEpPmSrb|l6fiX6LcmDUkH@>51rWpBZYY&5k1C|ZkQBJn zM14R66y&RNo^keE6N5#S(sd(oDA?z=4@ukf8=X@@ocHyFbRKR1?ZX-MA7X5l!H%~( zJF#l>rr+nuRZVyX*k}}a1~62-QdLku*?;*FQUes%>Qw^O*dFK71|trX?814lO<>Y5y<_?2L@mBi`CMUR4*9hM#fe63=b1$s2JW6-AqVO;MgUHbt)hq*l?STc~H zu-4*09Z-S(cD=8tYiP}J0A0#bn{l*z8nB=CUrHa7&=7vnCo%%@2=YAVC__^p1p3j9P6# zXr`Ct&*iIK^MT~MmNGC^Iwqq;Mjxiw35J>>W+hsiA;lUx+&4g2n_QAR=AszH{w;`f zm_q=SQiMgEEQZWXh$o?6(;mTxP23bManJb0novYetuJ(ntu) zlQ*NA6?hVWWkOsMcF;C4 zHBm9|3%>Ki6BnI(-2!+TsT+}Y=)0VD1m1Dh?9)|LI^#y#a&w2$!750XOlOEJ01r?M zLjQ;sZEw{=w+Ydb^yC+57YQF3$5#{Mj<@UMJJl9b)*c>q(OD(8ELE~UP!!7B0n&OW ziCc5Kl?e9+oz&y2)(_-XA=>de zjYoTre|Vv-#{DEgrW=Q~U=EK{y<~&SU&yX$cTmdKD`lepc*;GTn41&ssm2?>S>}~G zP_Vt4GWL=pQQxC=^y0YYAWPa0zzOXlK2X6F@0rtp{RE$`zSqZ`AW)uFX7fMuKnEba zJoDyy3HZ`Q+_k_7b4E4ZClvywt10t%aThNh@szqkSF(&`@<6JuI-G=%qHgHagqU1f z1;r@NWvG|joNHRcynfyEG>tv2W8L=L+8!&>a0#-t;ivaee< zx7i<#QYhrlROMVbAB~&%FHx&cIFZU>QFNIfh<$!3*xDXaa8-}sXDgi6)2K^GnAzG* zRNB>pg^FUT@I4V&?(uEu8?RnTb=nnW)(?wFbW0G-;;r+blLavU0%&_OYtYShG9oQq zFfEo}R_s6}%p_&+z)^hI<_obm`_!OZpik8Z7CHviluqE1z3(z~aM+x#>yF z#WY}doef-hFbzREk>2v$Pi@06oJ!8>I5qM17fb;%SGJ#8YYtwzIj%s%>223ovsf7_ zrXL?rm~Z@G2{7$m19#=VA$G*?4cS_pD#OArmB>`5k2j5oRsm?)p?zm{cySuLZL2DV zEM8O8#7+{zk!q;W0#mr0^LG#8RXU(EuMqu=GgYc8Ef=*iFkdJb<9U+?I6&$7;OJx*YqjBC!zmi(>16S8h4=oBgE`5*Vh+yVq@jr_b{bu&#Gq0MfpqjTJ zm<>Dw*8-W~bofQ^iS^~HD$811zj1vTEWHHvvEO|6Y$6rN`O$iSQpz^NJ)z==5J!ys zxxdGtd!*tt2Cf$L@gWM-vT76_7o|~f z+4_4dHLhYWTn$}#mj&4uPa-2N^92R$gwwP-tXBy8#Tlf6PJ(YSTFxiF7R=^p=l6Mw z;b;nmL`J>rFak2;G(_8*sZD~f&m@_BweZi8Z|u-+fE(rEUi!6ST(Ime>Z|QIX~q;Y zLnD#J2^>*4-pgiKt5JjpH8|=yQMjL~bL!i?NtKMRD_C@moJ9w~d}81gt2?fDv|idt z@aCCYMyXzOcXh81A6a%G#B2_-7Eg`g{9&DHjl5uu+Y#?{#=I0P?Jkb+%zm*T6vH){ zLE0?EGib%cAo?ilLbK9H>uFQWzDxO)eC69&u;}XKlo1?ACmG`C=?8Ydd@$S1(Q?1H zUg)}k;j7s=L_SLn!T()r%zDb?115;!fPPz=&tYq8=L$S@QE>A+Y-Sy%G;IDq^5At-^3WsN=EnYJ#UWyP07f-r&QD z{7C2i5@&pRw#Tv#fXG;qhb+2W{#~+8s&{rQj|Ec-R36B9AdB_hOk3qB z8Phr@D~^{q?=Fffy1x}~6DTMS6kpTN8&+oW)UHs7f^9s~P4-LH1_$4bQxz>_8S;}p z9N`#(!vLZ2k|Vy7;;Nh!0yHGf;7snqLT>EVPmla_1FO5NUDwOqnCI|u60vAY78`7i|pa#Gjd}nYuA5s0~=0+bzO`eM_M`> zXHGxw(BmK|_L<2mg=IqQaV-Rmuagfz z>Ew^A!xpb6zGS&PU)u=JMx8O_J_En?$x{NC`wcU@scB)hCdRi*P*hIZatna zb-Assnr46Jv8HWAq|M_l{~VIz<^xT{?KG@F=k8`$=eKJ*iVl>}a=6x7i{zEej!~e9 zPF&%LLo=p)u;_)=;qFR&@MQM#R_<-yG}lRsmoxVvZV~y3RJK5P>N{-&pIq!XRVC6e zI(Ku=MW_`t3s>A;a?JIqu-l@<3_4p*ByV1AOv`AkW;amEoebmxE_w+`*cp~eKO^f% z`Z~(JlG#AI{i?!c=DHF>A(F>A(jR+DlDU8`4}ZcqzV@{c2FKPk99A*!R)p#S<%9F$XEo3_S{N&bTCOvHadrrlkfG_D_YkP$Hi20=LkX07E^4XrWguN$EQDo|1JM zFir_AI&HWFjf7<<+PQLJ23M`@z1yfYMW?~kw;C-A`;;r)s+NPwfx;)}vE#y$gx&ri zR8Omo8{vYkpOFCgeL-L&ntME4J)xnP?<%cMjHdGaN*wbXUas>ra%z;Jzl*Kd3D4tK z_HH}TJPYxfXW|PeM%75^yGqE&>t-UfRX|(|zOsYCGGS4Z5&M12E$o+;M;O$rlrx^Y ziEdG~9fC5c#uGJgk(GSj>|yu#xblpn*-+O@7e7hNnj)kKe3xs^w(N3EB8wJ7f^w7) zTX+9EpNI;wx!ftA(IA6kS9tu3N}83dWiKwEl2%iv@5cCxIbW)K3zndq-!z$*S%$~5 z?fZ?Fhr+a#_dD-Ub?y$#wMA+diz=klAm~b+-1ZM0!K;EN?^0gBevMmdP8S0r|CaKW z+_HY2Y9)_T8T){ezoJ|LP2iY5enagh$q}dR{X&BHc6GBQB`jfTYpxMAK}>7{P=gS(LM(3oQp=^>B9EkJ6QnzKV7#iH?xvsI zO1$ZOm2Zt#@D2{AKddsWn!CzLc!)fuW zjnPJ^6f_O5WS}G8pOI5#fDzuImXhn0Pqfvu{5n=_(7Vu-a#?HAUQ`LFy?9jeXy4=& z^p$VjHm9}3n~#+I3~t{NX;MW)M+nC5_3p*&r&xbh`aJso{|(8@T{7R7JflEY!$jt4 zr4fB5`UOzS@TJIw%Kp%2f7t!qYo`As|E@=+M3q&(dp@IEP$#WuBSwAp_3^?}e#FzT z`EF!b=YuKQs-LPP0{=0><{#E|a?I0qtTgQkT%-adm8~&HV*)~-og^15(xh58@>$D< zbeK)PiCe3E^7*Uoe-bX}j%j-0G;G^;@Z`RT`?qrE$Hr&N@>*I&C~j8wm}ADMu=qtj zLEw)*S6KslNy3iu8m`JOlAnbA>l=3SQF8FtnM`k)W{GFz?-uCOiB9fNg;ff%L_5%$ z8uhYs8TuHC;iVhm(@7V0ZMRfzt|RJuwuhKUE&zYyz#wmJp;9R=SdPFq785<)@;8RL z8*e)5BsHf#3Ix75NGGRV>3vc4SnAVuHe%czAN+JDRxdwzktcQwJ!U#X5MrOV<-QHN zEYp12QKXwIi|q~^20h4^2l834 zX9B}XiD?M-$i!G86pC3`#9~DpMRNd@+X!J$C4a9@ew99DSj* z(zuVop=MfvUL9(EvO45*bw!p%-vxmT~k0=|e{uJ`k<0@FDIX*}vu+4nJ7R@Mly`79;q{z$7v?OK#`z@PX!YAJ|1%g>IK* zu--z|Cc~@h6N7VNYgEDY|1)-g&V=${4P<<8aw2f>GE4A_>#+HEsl`)C+W$31aDpo6 zR8!~IHUeKCWA+Yp9oD;f_7{+#sHUmB&U@-G)V>UCVVBX(KHnX}HhZeQmUbNHf+}|B zN;Dq3>&tYvpIWpP6V`zWtQW|dB2&PsTx^uA%hQ#BEzyCOa8hAg13$kbPPNgI#z6OA z$pTgZnv85^kXJ$hZA1VDxdJ-YP~~;md8`e{vQzXP1y$!uAMDGI#t`v{VB2;R?C2U|5>57)V+7|U=*QXuql{;G%eXR$fM z2=}uhwnm~GY~ZTHd0!ZxPkyDd9xPpn2>F;d*>Y&Pi_pXGHh%I*i=M=z_>7%IS92Rx zgArQH+8)0Xt^oCXMgJn{1;bmBb#ro=Y#T49$@GakV_E9c;hwT*RKEa(()5H?SsUZ4 zvitXmg}x%irUYBugay%MfPyiI~diS$pq*06!z22CnE!!1~Q=<}nYeCtW zO2vochvFXNHc4f)%a}Ypu?$uogBbKU5Nlk_gnI*`&+&RlA9(T?Y{jRy!%ES=1}`c; zv^XXs*b@j8_=rk2@y7XA@CF8*QFtS+ReoS7L8p{4GKk8c5bK4HWd*7M`SeAhDc~$; z;=F&W&SX_6ifcq6U^+tDg{yjZc_2gETnoETZ2Cr$1c%41ATBCfR7ZJW@?I75&S8qd zvrn+mn(;@H4u%IZ4F6Lb4yU+^(W;O-6qbC3Xwj|z5oMAIxCO=UAqt4LtR5gy*C3o_}@bgVX@aWh0t38_$ z$|_fQp+%?ZEiYd%y7sY9jozC+2tyZ3u&z7l@dCr4**gApQ>S;`5&R7s$uUH1zs90C zWO&UW2iO$KO{sJ@wpc89A}Y2v&4WXQzZO7gfi|{ArHs(Qo{{YLQ(Dw?E7T~MI+!5H zGBFw~)}7#bBN$z>id*d>lufViBx+dq+5qh5Gy`oSidG@03fYd)X0hWO*Q_Godo{t+ zQ`SM;>{BgHVcAK7lKqu^{&_(zD0%n+hVv?hi!u&-*wY^;JiM@_fd*?TBoOvb&*XV+Sh^efMW^zM@sURL`=bjkQC6PgX4iJ#7bl9hb zrCB*x0WyN|wbNue4@}7p!`7zPR=~d{?bCoo1`F^(9^h%ki6#O_&$5`gL@H{JFsiLu zYCB244c%K0DjC8{Qkz|^MI~OYSCFLSHyvRZB&8rNUd3PgHPu5`Sy(W|PN)5HY}?JY ze&T{7rG}wJr2~uMh~TCLAl9}cg>(wsO-><7pE74k?4R{uvlfxr&zLk6>tCMURw0^_ z;s8Lr=kxwh?Mp$genP8X#S0t9DzH>d>HneRLV?bT93agDBy(s_M&=Q&N0txd=6PcQ!pT#D=(S8RwKu{{TEKKHzaKuz(@e?BzuP?gLr7El4LS)tQywY4Q4X8j5KTm4e*u_(E|9T9z z;^gUlRF%gk{6h=-Dc%*|Lr_&7FJF_Osyz1P?4J1kpSO$8**=c;cAFejz4ie{<}ZMW zZ_$$fzErt!-mZRFnA^9>>uukK^BHGcV3mPA((Qc4@~wvV9K4H(@%G=Wo;Lx)8#|jq zW-^jO8#;Xae>bFtq{@_Pi{_>CbU-b{rE+CXP6p}PNF;t3Uq%L|k_&+WM4c?usWpbX zKOFlSrK${r4*s`n*bR*#MI&2l{QtfVUo{$HxTc|dFi5=`VvIzbOdN2-lH4v z6N)>FT2?5nV@{+RMx4DP{f>=Ko^aE>P*x)I$nZAG^hxONw*E6pV;20#@M65Su!2v9 zi`DUYw$uQuOaN|(Yx!&*z=w|nBG`2D;RlYOn>6KvUjVY|%QnR2?)-83qB%n~c$q`- z{Qz`JR8_Ykyy*IhL6z7tsEm>@k35duPY`T$)tYUu<9cf2O*ppjk z_E;*tzK`*@1G3~!$L~PV?!OYzF%dWl9=D?)7N#K$V*TqjQu?kUM-jvd=&{hzLD{#8 z0S47gAcy#Hr==;fKaca*Q%74vI4pc?6#BUib;PIFE*W1r$*wo(FvrN$456&2f88`T zdAn=FD;^_3D}HZwEsk(iYTYZDeXx?5z~xk}<$J(CuEXo|%||a$J{}F!A*W=+6gNhN zr>mE)28#@L<6vmLzxFuA>C^jP_hBv*p9$P3wI8k+_VtPm+Fb+@2j-XU4ps~coQDVf zQ}0DX?t(hj;nZvwRSXvCC@{o(&i`xlN7r^a2Gq6F1_9~k|Lmar2A`glYIHAlINKH9N5?nWciwbYKTU=NSqNzeaAk{U)JxpXZdRI$p)N6V!QeNrq=h; z%rhZWPRZZYs|G2DL{2)mAGtC&*d!b5_>w^+NG7YPO8r<@2otc#u)63DfmSZ;z5ba; zW3#;s;NgG}awZ!|+zNA}RVRNox!_^=nXidq2o5Q!Iw1boxbd>unPJuoMevHLA9pu| z*<%oGb;#-Ulw;w#n;(*P{dq^rk@cky%PsdDh{Ay*`hl4PK6fbyr>6qHz0pY3p^@A8 zh6LrHw(t8W#yOWrVt9Lu6W940*ZFHVw2;UkfqdTb5p^L|veQ&wRQXn+T+HsCk`g_T zsJzDtlfD!mnTEgiJn3N<35?J|BZ$P~v_u^U3p5DMZZz??@wU5z@pHwR^ zBC1Vu))EyOy#up-Zr)+KEF?sic%nOwffcSUNrnZWnYtA-ON@B?gH@;ZM!&ZIYUB>v z!29L}k=YL!4)x{VOEhSkKxJU~F9>cWb-}9$&*H@)Z_fzYg7wagad?5079rBX$?t?k zu3x&B#$Pt*-}x8$gk~KVp_9NnDk^}$Pt^qhd(C@OE{Pv;Y1k0ow4Z--AmZ2YW6tfN zieUWs*u?J>Ce^g3DQ(b&tsfur>a2ZE_oE>3ybfdgC_~7uQxR7@u2RgfPfS#31JmQB zLS>Fsw>an#o`nkAc#qE+klx8?tegETpX6p_gw6)IU6+|;2b(E#UIFSgZLsaiMOS^W z`~ER6@YwN3yFe~=;5GILx1dyv8zLN#_>la&vV;Ta`2hIJU;@@QUe0|sZ-B1~bfv(( z6l>c4!Ca7MWLz8^6*0I;?a_keBkMR*f^U#!iz6fIYdmYAspw~`fPj?Nk$j~9;-!>} zU>bil9{WmQ@}W7q$1ssHzhjb$70}g$Lw$()4mDVf85S?0%}hZ(hCw5Vxk4&H zLF{)Qa_7Ki@~G@&BF-nsrkAG5WnbFS3J-m?^&g`JlFgGAX#li4U0uNl;>BV}Z&py+i zRzcXB@Jdg+?dc+E&OM$?L4}Z&k$d?Ehmv|VeL4nN|L^`ws8=|LtR{Mc1hLtdJZQ0! z!Vw?9V&-gOMtLsC4}~B5{(o>yzuf^SWuXC&OYcm;(&?>AAwl9ZMA%IZ%>bpYvy*i2C1Ie zqhkm0VB8{8;o{X3_B7^d_EA{Kn4rN6A3&*@&v2E&8m@KvhN+~|ndYIwyoSE$o5qI^Sz+JQu?C2!X821ZjhU0y#qKHCoy&%o}`0;V?{Ps(xa$+xr6SyRPg; z@~b)z*s-8eUgJ^ag!4)T0{AYH!xc;p*UN7cdi)kayI(Z5iAwF}?Vv(c9LIQ(Vvf05 zL_9iO0oq-3iLNg%7t3*JaUDvM#CwM5iSwO;t>>$z*}SsuTXr#4OECk4l5lNN+DY*Ot{et8^=pO2SJz{@cX*z|= zrc4&DXveIgqAbSyIgVFIJ2=rCT3dnO%^XLI_YO!MIvd-3Hsh#YWNJnchfBGI+l`4n zbQY7y%;fi>G#!|qyEsUzTq>lX(EgK#!eWC-*;f90g?t9xnd{A6L11LA65oIlAk_|y zYrI4!cSyd4b3@&n4X$QT8^P83KxeD==$$=+aUjtt!v5eBfF5L>joIF6F)u`{r!fdx zP|n_w9T$v+khhQhP;;KJ_!7dDNO+N0Pwmn1*^q+8djs@5l2-zrqA=VyrH|zo+SVF( ztiUdtIpz4_AqB@tIf=Kz4HOEWt(c|!ef}c;@aEmGxYOP0zpZPnx9oluas6do`x~zG z`SH+~yObG&+a5XF5&3n_;D`^J7+<~1NnU)`aUnkm`f6wh7&@a-A4uTx6fEL?1+>g? z*b)odN)~AspQ?0zXN(y(^4nB3;%Rzs9fq2!*uQ(|f8)oJIIjHu>=7|>GcuK)(2n@5R>i9Sgan~@JcyEGa+@*zWV z0$HQgvD%}Hnfn+YWhEcgtr0h72|??`vZtMcof8Ur0SPEQ;!tnA8aq5@d$#6%3IdN_ zo1L%YW#+h)M&cm4-UnRoG)w!&tf=)wx4TE1XO#vfGcB_wz-JnZm^>(9&NTT}s!g7K zu(AlLYF$P_@d*YS0MoE)$ksqC-#b~vxopgjqCD4tYGo+Xd|;jl7ho9*Ad{%B$Px|K zyl?MgY`bhEG!DE(`O$3$L1>JhIin4U5B5b|L3v`>FC5pDlBlAv2~9D(n$532dnZd& zt<+qpJkdlXlF?~?foR`*tMClrx65!i3<5A*(Uza6q7+MC2+Q#-Ct9Crd{E>B*n`8V zyH>>;D9=oH`VNhNW4cy`^nYSjkhgEJ+ZGs!o`85GQFI7}@8+ zyYc?I{HytBn)9}O!Hh=x)%+5dqNq>>1q}#jM>b!yLnfH-C+8}*{w~+5euAg=!^Uc* zuA|qmU|4%$%Or~`j1Mouu#sjE_K{WuSCw8<)?3inK}PDNO-hxs5>XBnY>5P+5lQ#U z?01*H*$;l)jgFthQ`3|#6#G4y?jSW{4OWqE=`*!Do*ak-xC%l*Xq_+unF{9w$m(AI z<3WScCl?G+D3HECS+ur1<%rkm181odYiVY!Wh{A0f2DwT!1W0$UH+WMx&6MIFbIR5 zr;$vw729KkVLyLa_%|&NhpVpEb@48TQpsc%Gmj<9{c$C>GX^+l7X{73wyy*z0Z;yr zR<30k9%u;6fCN_235}|%OvP9~*H|#1O-6rRV&Aknw}JW5&q`0rqKe?sS{T+K>F%+r``1XQAH$fm&&?2Y!B^RF=fgpt5I$` zx5fBoJ8myZrnC+#pZk>&=6L?qMAc4`j^hwikiV4@*4?{qHuR;Kya-t-6wrp3a57Bt z>@6h?;>(HO2#(UDPc=U=dXDk;0)*W9qY%ZuTTGid>fa=hzpCqh0d!FOD-v(gY5L^9 zN8+Epxob86jDo*{U%-P&#Om zSgE23)aNe89POR1`gw(8A5v6Y;}~mh8+fy1!?)X$OFBwt1p=P)VE48jC*~H0wrXp! za}gUJ!t%6(B=Xoj`C7PWVWnbIQgXO!0qd>TbrZ>1W=Yt>%4qp7^;k#=^Wxq?jKr-X zJ{%{o`|25IL4LRkXNgm^nk|F06WKX44Rp4I`e`Im->D3}re|0rCbrk8e4|C}{bhqQ zW!Q(rA7dvvUtB|kz7ooetI(_todb}yKn1keIRmt!KVPuDQyp~a;0_oTd^$Je39qDQ zH?DV^h&4kQ2c_G(tI?A2DtT1|5HFwg-8~VXrKekLo1DvBqQX+DuWsxQw{yCE>I9Si=OM}sU-(#`vObdwZPg1t`q2A2~xnT3sNd@6B$ z*4tU-6aq)x{eq^vk3YA_jqqJT8dEeh16$h)Fy7v%@3q+4LaZ#PA>w9{LuIW`3gBVl zVMfvwM{2ITega~823d;eRax?_&2cjK!g$suo#H}4RDJ81OAkMp@*S;E1~!#sU=9Z{ zFHZ@66JO#7Wm(1yzpLE96$vQ?Oem;eLgK^JLJ`W;=>$p}49zdN>4=0h&3a}iJ-%<) z`qagd5sIVN+6^RVSt?+P?|CXtA1|I9Bzkgd+!UHcmGRhv<893Z$ll&Zh_!hPyIpx3FTCGWqPVv|ApIvWjh0h}DV6t;Y|J>g)`QYz-q;Vh zB_-J|uXV(@qP2XkmJDD_042YBr9G+}1}=n&gCBNgFo_R$s;uC-3%jR|F)M z(|$n%;TM6fHI5a`$bv=#jmBdNm4=FCRaRm{wY9hh1N6MFWR=ANgy7P_{7xba+FRA> z0(itvqet||PDyNJI9d>=71kL|O2*sHhUuX(v5~0|i;X~PhCTO$IEk;NMFoxe=`J2n zm=6(v14#dK&n>ssZJs<^rC?6TPdGnpp%%j0oaNCF;72k zR%2}>w0lbY?fmoZ7IriPZR6*!s-CA~f6VSM8*(B@kg1M^hhzJ`jjCst>~B?5YgU%{ z;e1K?lM8ty^5Li<@h&4>mP=6(;vIxN+XJHwL3<~Br{juYW;wMW4tLFi5Z+YdkJ`s( zQL)%!#4pcLzfEBH=rElrX3%gyYmaM+-LKr54?bEd-OO2=peP)hA0BN?X?f%>jL_sD z!jsB4%StY0_C$_XJwbc2Oge`~&tdGY4FWF$e*qvavP-*L0EXyD9(^0)ciWRX&rR-o zj33UX%1uq2{{rw39>~m?auzZQO7zx&$kEg9C#xG@9D7X86_*VrG_0!H>_#tEJ8Bog zpBPv6+uqD~kqnZ)>dDQy4*^I(UY1&U?TXO6d~}pNv5_0~O2L8AAR$?HKE=>)a0q^{ z`Zy*IB&s({Kn&48cIPsSn1_<1I|)S=BX(Cw{vB!hV}eGJk5ymbe`WjYT4J#aG)dlMWBvScb9v*OoU8`1}1nf@xO3u-DADDBHRpWeu7N)os08D z`>!2DG>~lCKk7(J;1dbWAaS&Jt$`tz(WQ>5%ZT=DF|VFS;j5HjCp3asyBX5GBBQ;G zu?lD^;w8}1T#`c}EK{~5xKSSE#L8_(Q+TFYQ+JA;BMO(U z1dMK!nS%mKD!#kMaFuF}AA=zuBEL7;_VLnRwRtof$=Rhpn|hW*mT|35Y-*r|_YEi! zIkW;u>%rH6iXTDxN)eF@$F$>>KtQ+Qpk9}0zvYl!Y+LA)w1YE_381lRb&9ykG=Xi$ z>bM0b>#e2KQxsHEQ&o|$+^RuPR=EGT$CL2mJzG6Vm7f{Me5q61)>8+TlbI3~dd^{o zTs7%ISs1wtL%yAd=0lWU!&r?d!QE^V!h$0eGZqV}@d2Oh(QZ~NPfE6=6uSuEs2W`o zVkgQ^=TqJ<{vHSg=|Uunc1@IWr!$z(Em`EovDwZypL6aS*KqoouLxvf{uu~O%=u(! zm3oXaPx^?%2<_n1rd=rW-P9WQQ*Y(ZibZ+>k<-T8;7CX9w|Kus6m0v@W>iEGVYz+A zvwJ;4OqyZaYg4{Cr9v|d#$_ra z@TTUb&TJr$9jDA(urFV0)O3ccBEU~mgd@A7yCVm!J6%K_jNbgzkZLS`Ou_)%{J!X% zt29xTwuYymwvPs?MEGesO;gt$T$Jnj7;Fyt#bdG<&!lkF(QvdQ`FIvI;6B)~nJ>8_9nFfd-Ys-!bekd(!Qxk9}m!9$nazU|FP@oXYQ` zN+(XBGyq+{=3H*m|9U1>t8PqQ6Av85DTNUO^o3N3KF=6DeK;bn#cn68HUh3BIiY4; zh&@L@$QEYz+k74++F%XE`)3rtc_JTc($(^ZEse&&DT@)SRan+=VFjJk9N^_ zKjb13kty-LBEgIL)|#^)+2wfnvSYvagn>}+Jg$*`c`>(LTgGP#(n=RvWr~=5)83N6 z0-$dkkN;7`HFadgcUPMjPWz2$Wu~4GKc)?4`yYxtB~*h#Ci_N8UfA_VBLD6412dYz7mtapXqGsXD8^sZ?C;< zSI%cuu64&_qqAkE|0qP&Z@imAWm-x!J9EB>*QwU)-NwiZheAo>L)b0`;zT=3U(^N4 z%M@I&86c+&v!}4mnIWY>%VPnwPIF;@J^t$Fr(BZkpgt_2siOp`KowmNj`bKm<^_ys zOcfSo9gUjwFdnuVrwsS$ZzOEYOm;1tx)m6n+nbFFMTp5Tbb zp^FMrjg@=1K5CnEV%dvR-3`kazC8L)Za{}wavHA5oJZPNnNOxo=Mm_`vhf&HT{uBs zpp0L-ye=H;q1VicucSLor*+J7NT%c7KIkFIdwd|| zm8-M&@V_zM$j1{#W$ODRv^_f<#@LLab=>8)e3CEh*l^uTGJ+kfYD^$z@u(IrUHlBL zJ3w795nF6;NUFH$vC&@ACLw(P)?vJigema#*td?d5!~8AC)UPDaneB3s)p>)kn}w z)HvkmaL58E3G7DJu68Sktn>)~~W1knS_o!_im)AfGRb=81c z%rcU*(el!JlyXBT4vBT*2eF&cZ;5>g=YrpmG&`<8ty7S6p5PbIt`;=y(PK`=$d-+w zwj~_2`rM{|^+3CP8cD%Q_7a4bi8U0bCXfS!&WC2M{TLuu@Q6cR$(_y`4e-|AT&T5Arl9jJ{yeM)! zlE=fd0^YD{aq3RC;|pg>oo_V~Hr6@R$Llg|1le`wfF%Qw;dnZF62}BsKTDVbRG+9; zWcrX;@Qm-}G%=`7?lLk*!*ciRFZ21A^MOXXrc_py1)q?mzEc5|!Ybd`)Qhp-wPM>Y zGQr9Z&ES}am=tJRbo!AhjP(c?x$wmFEiFq!k;mD=;D_&Z1#+}UGWdN+D};h=89+D1 z#Iw$z)S8~!u0}U5|28sf`*WAhyz;!b6FQs8&4i|Ri?74}PP=}iF0+f4ke`Mvf&^%wGc8daZ02jPd=dF|<1 zU{UH^zVSWPJRqMDpJ^rGA^F#zg1VabJ!)FCAG^Yr^xXM9^^6R9DV!v({#0VW19&R$PmJ z#n6?O?RQ&xty~e?w-;m(T$^zDP0arsI4srv!_Zz-T^EGMw%Zd!&Jf3ogrz)ve&$f-KKE%1$L*bCljm;3}MKZx7H&G&K zmgo5Bpa)(e+8*)008B`U+Awu+5U`{v48oynLHQhP1~ChROMqcdv`WcW6--)O zGGmz=W&G+UW7lR7i5F{^)DOS*klf?6#AmAkj7S7T<3JdHG> zP~6p6|3PaKwu>=-T>*(|h4E+acKHs}j=H|SAhtAEnwDj@@+t`QfU6*XmT+S2;=q5H z7Zk~;^JKiB12r#_yiW-Cq~IW8C+}#yZ{b-ef^Q(zWGWPi)-#IVpx>ug7G>;o4j$3`m`4l;mzNl{gb^ z(QF4539yRUFSsBrn*BJWz;3{qAC$@4+niuARH7s% zX)}=(GFcEu82*wnC)U0=RQ@=*oE~M{L)@ZHjD-C$FI*gQgYCY$`PI}7z zY63LsY1RZBS(;86YYJ%L_c|47%4z6RchJ|) z4ATFcd5wRcd8?{O2I-%tVinSBNQUf$keMF~+$G2vhVeZWS;X*mLhJK>nEyIfY(!NS zp>4u&1ZIYFra7wZ$x~7~`QP+XMJZMB>FKVEj@=Ia9akCrsyn%N*V;+&u-VIlectY_ z^RFu*8-bf&0A+qDTT8;kE}e$gLiB8Yo6E18(PGaxm^ioe(W6BhVE@QDabxWD8+<0e zKqt*~H6%l)!G?5TH+fWfc`&rw+$ZrWHbi(?bq>LsCf-|D_Qke=+fCMxay~vr2>TYk zjhfgLHHGyue-&W~h4s$e_?Qqe08h~7{HL%vzbQW-lPJ)t*tjx+Vvw|1v0}5;yc!K@ z{FK?vHr9i(tWuh1Rt9I!ZQ=K)+<^1b5`SIf5MnLDF>-zR{RDpIT^F>Z%u|1}}UU%A|aWk_jh1S8O2Fx&=fa3z_`*b!1_>t%b# zxe^BOvUGnPF3uU-v2;z z@9hK6FfEIv)JqilWe1|@b7hdfh303!h2}x3#`v8E7djx7w;kH@nC8K3bYECbpn6E> zZ>|q--hutP9Y-OJ*Ga$gPEPDum<==T39w>=@IXz;K|-VBhV4eC`L@g5@5t(s_&4DyVSTSyLMPK;34Wwra!t$@VgQ0084(kF5NE}Q4z9bT|*UR-HS|ae4bO@ z^w97S$@NnWg#W>w#d3v#-j^G|iH7XOXW-)Hr+SLJ)`d-u$s z<#`8vb*4=E*>K{)d&&vUN}=q2Mq-o$+?s9CrQRf8#;Qdt--D~0D;df#LV(r!aU1Pb zJF4PX*tn_y@G;ume$`gDz?YN{WM{*#6S;I2Iiy~AHT^KR{7P9Jz60>Rs3LT^I4ES9 z9%W`mr2vabW}mfVnuyE7oZxU5R>o#225>N_p&xa{Sxe;@1x5F@{BuKRaIs8rY0aO8 zmZKp6wByW|O=UfOg0plp5~I*M`du)W5>8Icg4SxeBZvIwJ^%PbXGp$;I{V{C_+0=7 zfdZ|fLFQAtuZn^i3sW0AqlOBY`|4UfcWsdqk#@|~RZIl0_d32|L z)wJ!xp?9Q9m0p7MUPO9H2sNRDK~AYBN(NJphA3aE%ED*ENV zpZneK)84(mAA9fP-G3Gb$;>sgW+rQ0bIp03XEXa0Pi7A8As<2X`5(LX*MFKiAbnwf zOlz!Og|lfhX=>Ydx3VeZZq+WfzD5{nBcKT&IxVG*`nO|yt3SIlU(SFCPdYk_p@P@* zXv8sI>;(b2hky%}mmHu!NDT9V3?~it4}awE7q!+AF(?S!)V^)2`$~ma)Qw8u4CbqD zTxc010RVj1llb=?{Yn?SEH~!upYg*PM^Bk$YL-0D21upI? z#Z8-6xmOen&o4v63vXzTVG-9wt+p9(vj^l+9yJ^R%mIY*DE)h~D4eK7V6L{BBBQu% z4dn=}gag(^{NYu3lCEA=3nX}i+n0!(W!iVXgbrMZ0dC;OQ)E27R})dB%sj@GO(rvE zFYkaDx5A9WqOZnhf9(nW`yc8jxlgg91Kb)^bmP|_+be7z3-Y$~6TPEZf~YZWobeJ>nYLT&X_szG)5#YK-q;f9wiS6)B=N8xCh zN&llxCxHEe$;m`P?a_@Ji2Dt*(nYHjZW6H<0G*npXWv6?Q7fAkxHNJ7Y}P{XZ@}@f zzoVS#k(bNKR2Uf#iYB)Em87OzCbJ20ywKug9^oN^Vvm~-J7nKlM7KZvRgxzlD~Fqq z<)wp(zs!M7dh=`7?+B`4M3%Xy22ew{qS9Sq+ffc5SI00X%ZjrDMOwW7Mc;KyR}J`2 zro(_-xRx&?xXq!&sio4YI$2``8Nb#k|LImG|LOs-5_Hg-4?>zaD0CvUT8_kuxJy`3 zE00B-$X#e@^Quebd;S`n|ER&BV{|(YoGGy7%6lzVm4Tmr0>!n)Ox+q7xHN z@3qc{tf4L{>7G>S>zLdX+o#oWCXrFAL)v7EH$TI{*aRhE(`xWZth|72H=$Ml`v{NX z*n`gj?Oo4A&zXSfCzrU$_^q@_jv7t{OI>(RMJ;QH>sG-Eww7)4aI8=N3zkQKdg#*W ztR4-8U@&7gO5D2YDduo4f}M77z3{4$SmSNrCSktHBN??ON*1*-QyOY~LI56McASlU zK+5W3vK7?dGPv8i_aqk$r5u+Gc>C+qvmf#QBIG^LJ9_N#_Zp>7B>t2U_yugL zO~Sf@K#Upk+JbRvLs1yK>>hBf1}`c=y%6L=Z?(TPQy|*0AuokZ1cxR>>X)eI@05gJ z7s`v#pgWbSU0aWP#r5-$^95eI;%vwVE&|*wgbz|wP<~=!!+jEcC`?9mN72+!W11s% z%zK>t(XWnnAFYCtQfFvE%i4NJn3|ush4jQiRdK)Ety}m zUf9g=&9#$LC#ca-`~vmTUjCr{s$MJW-cUTV&e|TFm|TqcVR_6c@9%Tpj>-<*9iUxS%1fb6B zvTq6hdgI>*^!`DP^Dq6fpKki0=dZZos9*CwpB;bgzxn5whyJ?f-%(_WvXm?*H$m>Bz>7uPQ5K?RZ(B-DCWa+HnWK z4WCu_r+4$Y#X#yK5DRvvbwH|{*GuHVL|f+vu)mYl)`MzA$%fOur6Sa7@XoOz#8cV( zqEkg?+SGw`q~zN}esyP~n|^6GJU~ z5dRuEG)?KhQw8VEYU$kDp@;Ogkh?F^AHLiEF?{Y+AMk->Dy?z8pHo1o>+Z)e)PJ*& z;hw5)GKGr%aYkee!!dqBrXNVYR1|h6Tzve9J8Jk}%^1b$6BV?o#nr`L(Y4c?mH)cJ ziT)bdmXKD8@8uBp-iI7)1wIkidUdg`rBu? zYdrhbaWEwZap~*@PMxPOwbu|A8U3R??wTZcds*bo&8}nPHB_92$8P`$uC9e<*g_Ds z9Jj{)l4C%>f^a#k^R|ubz|GGdQZX71BnDFK;{*;p?dt)WR_%?CJH#!!v!E1odpFzz zMoPo4wKk7Nzlj_4crA5VONP)taR{PEaNd7HwDh#+ZI`vuC!A}GOZ%wB-KOJ4Mo_tao$QAr$q5tY1 zZN4rIw^N_G^&1cs7`h`K^wwbTG9)^OqyF1X^{XFG<5a(gK?Z+(d9ZZ({B?M)t%`Wi zqT?dnhXE?Pi`l2&I1h1pi#vgq?PK*HO6#x05A8^FuL?_}7=KK>`(=y@u}}}YmJYym z2WJL%8=4>XEzaGZe-qU9n%Cb6p|>CKvd4z=|D-5yesb@I?auz}Y$6wEo9{)Q%cG^SU<@_Vjgu?^y`W$^cpI%aW&Xs>W}( zQn;U_2i1Ic`fH$ZBSZIW@Dx7c)wbXZE0zYPDUIlmB19Kr1iw+%a=?5v&S>P?hxi2-HB8w&} zGnyYl24!-C^Qr9(72e=63n!v#xnhUZ0!aT2;^g0Scv~tk-~2wBNS0KI(u9IkYffj7 zTUhs^GW{Yk&A;$LlnFC4^eExKh(2p|4`3f{zE<6 z;}7-h|BVItsi%Zc)5T?qvPKD&NL_=0=6N54V;d8)e~PKD2A0hwY&WGQ@_)Z`tl*fI zi-9>kGp?c`2if*G?~r{I&vBhLL9_f9qV;|>OU*Ga8G{hR#E8SoZbDDxdw;rVPyck& z*8X(UJpc6TI{x(QHoyMq*MICv(bwlm6}`E2S1Ra z>AHBrgC6Wa!%3Q9mVo3`Hk3N7?73cnZ)RGi%q}knkH?6PlGbueN?>9w8S^o{A)Vxs zKoOr)m4SlZ|GUNXK@ZYzJ51b(WD-tqz3&KqRlru7 zB-JXM`Cc>5KWD@t{G}LM80{mOZ=VAx%Bq5pfE&JDU)AX9tJJlkL35D{^iQ7n<9=kb z{GYABh5HV$$Q_(<1_u5wB6V*#2$k}s(~n9%ORvNmv?gePntCHpMG>sMd@eeSnzg|UsuDNq zbW`FD9`z$d?i&B|IY`?2ZFS2YC;m_;e2>wvwODqnfd5s!zmT(G@HC@Fj>fT2;)Bt~ z_xIy3e!2hMa6wWvf9`Zr*m+u@s098m{Q_t5O+^VEPRQ=)7g?0VLP-^aY-Utdg;$ZFf(7CmXz zma0%K2@T7Dip`$vsJ-&<{uw($8wVB2oql{smx0S8FULXQ9Z}2v)rLxjTIX(@bE0vS z9!|#%%{!a-V%iP7V&5OIWrZEs*napd)M^)n@=u$vVfeypO3-gDx#U- z#o`ysc@ZPlJ7yAm#IH=$mm_+fx>vIy3dJipq08}AxdP{)Jnno&c}=8ng+h{wZzoQ? zK$eQ7C2%kckj*IOF(ataT$^Jo2Fv0xXFHnXQT<#mki+ympmgw9qsFHlRe@eAER zsiE73vR(SdfZwxT8nm3ZW0EVfS6e?T+@9cv4FMF=cr+7zibObHF?@?lA0Qgcrtb>0 zt#{h=4lKIf4$m_TD?T_tsq_H!je&cM%s&MqOsM{_rm{+MZO~3 zMW0_af#?n5y`WdlnL#I@$PjAu?m|K3Uvy0d`Fc&a#VVrkm2`#xcsPdn5PpN&i;_v0 zzC1RH%HEJap9x#1LM9oR8l(Gth-N~42AfrfwiV3d>oi_QC=mJ}&^SI*{?E2Lf^AwW z;XHRRKVNuAs~P)=w)lm3$VUzF`gUv3$ICQL&H#xR@N+}jYi4{C))~f=nP~#tM%joY z9c9B((8o0uhYWcVd?)1VgeWXax)=Au4X`6nV2bhniC|LMZo!E5if~_H&184fWb7G$ zhwT$juA!X5hADW@`EA3dS1##Ip|S*GAH(j=t5YiA(zGzRrp8LNneJHApt*;3pf!Gu z2Xv1--QN8Qd}Po{y_LI$M~4IL_H*&l)vO$X@h2&bL3CD(gzhX@WVE6m-Pbvm@*FujOaU6bri;k66Y|KjOnAAWxeYeWy=qH=%~zib zcNI#dD2M3P-zgfteQ`HeU__oGU3-99n02;l@1FU%@A25ibl{RJMh$&JhN>*ZQzKW- zSbRomP-0rhI}PNgWOhsA=P|d`LYNV*w?q=}I?{a@@#HCI)Ot+}Op+%cvE?z5aZ@VF zLgr#ORq~s8qfZ0MaOfJ%Bs)@+R4m(X0F0*s&5EMFXgo(mNFTBTyTLn;7n2$LFu!V0 z5Eyc*x5hubIvN`{wE{2X+jzoy$@U{B=*mDimPn2<_t07 zJrGGyhhOs6TaF@F<%ytTk_K@m$6E;%vIta^ z2t=4)_~kh{St3=A!j~jr%L)_%8X~fX2AY%w8 zn_dp#FxNL-1_qN_Yb9fq?83$;yKU+w_oGBJsfZwD#?)`hRckB z6AH^Id41oLekYx~e^o2xf)S%is8QGUE{jMY$_B=(>(Dy9>~W2H^HzJ=WsCmu1vi+J zQW=dQc|D;MK?Ad;m&zS;5OU=rO$#7SAh@YO9j>D(UO2d!F5n$pN#~q~Xzd(iLlVDS z-zpuIL+ZP#{|0RFK(}_I$wln23>=r!Hzqw}yb9n=Qny3d(GXPpo9rYN(FgQL)xUb! z_pYBpQgZC|7zs$UxKo=Wf&N!Wj1l+7~8Fqr9BBGHDksUbCh%^?-Z6hZ7VkfT?SBoxI* zV(&M~|8h>E{0A4zZvfo&aZ_y}#pQ7S(&rqb`{`JkcrVfO@8hoq*bb6{i_!Pn53`Zf zZ-f)tZNEv11rYmZXsX2^jM@xtxtVDT^5%En{w#;6ky$V<)2z?N$-mRzuofa$b;{FU zi9&vAUvfScc*n>R>fFSGTS@?8wj=5>MD^G2l|8a5cYRaltfZLUm@pc|_$QJj5I9Ao zr9F2Rw}8nYlPYSRr=EcrIQaxfjH=h8g%9~YMrKolK5B7qhj1WNA@!;#IVo!US-s?F zF9yJ_pAzO+@##WbD4e#L(3Bp{yW%R<#Q=Y!l6jYphrba;L95)_-H+l+Q5TQ0M9enXCW*>4;|Lo2RvbA*%nCnBR{c8M@)$wg9T z&OpXDYb5Fz9l#+1IwD|r5TEozX6`L3k+r$TBh8vqR}$>aLbB)p(mI@ArYRsb;=wPj z_4hxxyHK}U>%xtW;_sXgC>*4oYYv%6*C-l%?EG4ROHZfyT#<9?_xX8IQ{OYCyXBU@ z0prq~$QF$mj`&}IRdn7{sh?Tp0YtOw-SH!|vK|S^st*qfr1p^BE_sXz+|f-6YKyJB zpbe~5C7QiQMaxgEUqE3Si{@k7vvAE`#fh>3J(fVel&(a0Ml2z*+t8cMIGm5 zprluJ!OO|uk^H^>T>VVtylHSzCf{_mrUU!%MiT!@&n86<*?lStfLx#%Bm&B?;idtj0bmYRYRskpOjj&`o}4;A4blqPWsG(L+lhn@1vWu82#%Fi}c&d-G< z=f^x3W*$Nz7ZL*=Jnr9;<=d+>ZSgPas1R0_0tx0Q>N^oLL{Rjw<;h#KXW5c-XhdO! z2$!=&hO~YIdhzeB0A)%aFHmGVy`gJ8jByre_Hv?IR|DHx%p*2FY$U-=Hys)_+FVI_ zva_?v^0;UKl-vUai!f*#-JbJh6caWWFy|HSEq8kz>x=IeSTV-|!&@^cZxxMh^P?;5 z;S4n4KQw+vWcx)M(Ce>lN2_`kk>0_`K9=0hg1_=9X~mn_Ad!s^Z=)N@d#3Is1zZjR zNsrV)J%mnqj&98$wpYzbShA3cdatO9$|9S$`WT{HyWNp3?d{+b2zM+m)0ORG#J4y( z2Hq+X4^cawKzd`vzX74;-}bqUOwVlVQ~=#j)f1-Q0Fm(Br5xwf z*(*_Ogw4+F($^8@jSU)`2w|av@iVF@a*w3XR>NP1u+EbzBX7R#J3p_Vvhou4ZDi4B zV@D-rrm0Kj%vY@mt?NErClx8FydS`j#0X>Og*UCd=8}h8Zoh3erTcF6*_>W_2~*i+ zM=#m|%8^|eE))t|1<-a(>{l!(vzaqm%k~c(6uG8yU$L zz$ZwScr&6TPN&%X0_PbmnhewDV;>dmWXS97&@NcN=8bOflKiS>SmR>1G;zchj98#( zxE?Mn#0TYtjgrp-23R9AKGaOu;J<6-BaW>dmdY|~~B1Pi&=(PB>cI`TCY0H7^|>)1?0uWHkSW3(x_yXq?^*cw=VAzL z7ZJ21RMHC=1%s+PnJX6!RLTzLmaQHQkI6g5I(d_u%vP#SwZ^PgqOkWn&_OGZHYR{6 zzq}FEvV$KUv=_qo}+iI8dHp-f@Z`Q%*vH!N-q7vBJLPz3^P& zdKHv!_M2y8ltj*Xyp!^Pwv*Hw2=Lg(R8wZKj{y7tl4Axj z-EFQ(cXi&oVD()#D36C)6gqFicJ!ILstaZ(CLp7Q3a+U+Xb&^jRa6$(m5f%bUTl9aD%VS>06f12QHPUE;_%%pE3Hd)cZZ#v4L;slFr!z5alNHs zi};>9y=+y_ff@0T0Zr2%>LGd^ienH2{%_uI0;d|8$K?ZWqkn)dX4zZFX1;>b=rN|K zVP8c9zfr%Q$90aaB@@Z|22k3jMbvZ&vtG(ZX9lI?LLJ*^rLOhJQGsX6O1+bm5?4k4 z#>%N+RFo!agKv>yzcZ5aYAh=o>BJ`G1br3^GiL^M(9O#88160ouxH8dIG3-=-+@83M3yHh@FKPN5qatvscij7jaF}4vdC1wj_*GY zgLbYKzmOQ&nmm`zK}unn1$+o-$8b4<<^r&)k`ixl(C$oSZhc*4mWU$&ZxCkCZ+aBh zhE@@X3SdwrQJQ1&rRoFbKv7k;ZLXooorIhf%YIU3Lo73-bepm&u7;rM0&zX9fp;1YWwE9ohzpVRaM zb_Vr1V)PMkg>BJ-(NG_2;YYkvOx9M4k7miTLOmR|Zf}z?4y}p#=Sd=HG8b!)Vk8L( zpM6_CS-qB#W^K}V>DuPkOMy3+H5E*bfkOeo;y3tVV~OpJm65c5PR#Gb&sHQ7XR88J zBx`{awsYBXW2BWxC6t(>#911TlGcN368gkOy0K*z&aJy8Kln*snuA4S{ zLVUa85UF&ZL1zz;pTZ{;48W()uhy0%O6asjlfP%_Fsi5Upb{3m#oNr!MaAueT?rNKVEESbM=Bv^6^n;b5hemKbl4mY<}8 z*olb600X-`=cuQEk8-Eky?5?LptQUSpVqL?zFeGzoVrL&Gs;s4Bt3s$Ovg?yAK0@8 z5-kAJn#FWr#hEMeQxa`3C2&$aLTRG!92^NbmBtcBQHT;j2?Pr?Ti|ux$m7Y_Q@}^m2ZC6lPf^`;$=RcGj#^Lm!sjsnozBhMOaAZx~Ad?{{_qQ;A zpPi1%E1NG>2B~Y7ji=j24?a$8poKeZMO0|GO1L?faJ;U9x#F@gmF()6SG`Q)<1C7{ zt@dI@4N?4pQ*)3`aP!o|gTa7EErT5SFPi&FVE;;zvud>IyDqycHfEY>7u|qlb*;eNeyDUS_((8| zF5j*0Cx*qb_x}xw!5%?%;idz71+!A*v9Jizy7dG)5@X~ch z>27HSrsWAeD69hwE;*Fmk!s@Z!6u5YcgLk3vlry9V;ZuI80;kS6-p(fAXdEBT$ySL zF1qJlwR@?BwkzkLWY`NYF+(F6hB;#pB<@&?3RNQs$ru0VlX54+qBTDmTw~g_VzpaX z)Ob`y9XldSYPklO_aaywsEB(2%rv@B--_P2Yeg0S6>HLqC`0+?{d_}emde&Vh{dje ziJ3;_a=ip%>MSp7k7Ci@e&dz!}9h*oQd!}+qhh~FDH_Ml`dPf=B^tYZGo09cJ03bBP|(# z3Uo2v5MeIG(W}{wxIVsFcPB(5SGW-0pnEj2+OfHJ61NLf?P@IA({+yJ$5R2R*(A1w z_5vzjzIToyw?WZ)Jc=I$Sg^SqpO)$KVM|7`xwDj2GvJNjBLgU$-m!&HyflQVwg}`p zX>=8HC0Y^uoP>GIti?Zg+^^d;HNrD$@k}^ivKrV{1Tu`Eh~^0-Cx~T~DT;nPQMk#M zxU5W0CC;Nsx6G1qre_YWk-KQ^5XyB}$7%L%$Y)1MPtXEkU(buiJH;N0k@3>VL7 zyo0#cOJpm0THX82$#VtPdisJo#RgrZDzSRyP|ebFn3Ucen34Sl^+QT~D}2Hs?~n^^ z$a%B=-@itCR`^|gox%Pzv9c`=vyW+Cd|QuXEF$AgFCb{5}%CkM`M!D%^% zpS??a`ta$s$=?bo4eUMpq5-mJqKovQqTA}z=W~=jfB4D1_b(%Vey?lMZ}F=xxJyRv z3|402+-$SYsqWI#6Hgnny1A(u@^@w4eNFlectOgY%!H5Uvldt9wNss~P;hnU!MBlr zDMf7?pzD1|7PTS5G=G|2w)Q4XBZeIue)1<}$iPW9y`uh&>17txM(+s7+Gq2uBIaPzD(&yiCC zuus-&&DJy?U2?fZQmEF4Pf?mp91s7l@yhy_I7kvq>~n!l04q)efn9EnVC_~{*{3&h z=a0-FH5`p$@@&6g|6-m+3TK{AtHpY~fvKNo+UxWVc~tiw_BA#&pZaojJqAIpM^w1O=ye~kcsjs)e{Y{e&yHK+=*(=kZGjKN-b{qsIcYt6t% z<|vj)x#rkCGx6Hv?;9`Im8z_K9q?n?!2&l9g&9T&$0NLI_1yan>9b7>xy_a~LTc0x zCd@>z9a@KPN10I-2<2~TaI4l^b}MtJ;0j<>Jv{bWV%^(8A$N$NHcXT*cmDX@8I=FY z>&E;!yJ;y1JNph%8gBw%YlNSAFy+(Nh9z~2Rar6<5{iy&sp))-QyDff#WeTV&R$C? zGz;7UW%S z9)=c}7Y4bLja+12M|=wk<9968@9g%{2leh!*O)rjAaW1~Cp&E+X`oTrxQ~;wQ1z4NDZ9Isw{kphs%bPIQhdRuS;A< z$_j@{p0qvc^8^O}cE7%$uVRv6uK(M?QU!O#4)C6bRQ@1*QSNlB#_fiHA!Vk{m{>M* z$o}=m&76EaPga4j*HM)+f`~|}e!NBJ6ex2A_v*l2bJld>j7bpRL&{>?Tig zu0ApH1tjpsIHL$wUm7)a#HZ}Q8&}W5PZl&u;B-^Ll^L?%Mm;Z27xA9Ehqn1z?7U`! z`~5!VSfF;R%wLtpaDNt$jXZboXzP;&Sjy)h8^p6AKRJj`qpoaQ&on{95F^Irlf{Wh zcwgYJ1Y)Gt+V0n*=)@9_km$wIGlQL6Db{rx>1wjyL7iEF^@reS-L^zm?N)4IxqyUZ zGY=?Fau}wGNDvfZN64;VMDh) zD**~)sd@JssT&P*)5})hKKVq@OQ9?@J2)_n6s0yU;ZE~@T+no;^WMg={09`@A-vLr zos?M8TR{!1Sm|Z>CTGBMXg;B29i>EK2zJpTXKPD*EFyY7u4yr2xw3L7H8kEfl}x|` zilka7ZuT&)nMG{v(pd!_Wp5Ct7{cqg##dh2WU6B;7cwY`WmA;b8>!tps?B6pD{k}L z)$U^|YblOQ;U7Z52f3P2KJW-)RMvcqw%R_!Cr851ac>P)-^Uo- z*LkOs)sa_+k>+y+9Wdo_Nc2R)KUgYD6zz@!Tb03gCMb+xNK&aGC5Azfha_@gY#)#Be-?J3L!}b&DHQ%yn<$+B~SuQ1Z83 zM&S89RcNfEBAvjuY#bk?(t}3egs?d($;4{l@m@icVnr_s)Ana(qWFdOO(D>n^ zY2>mQZ)8Gw$ZPH@uD1A84g-6!9;;^ftC~T7?^vl%KYMu#Vrx6O5E*gC{7H&|ViBt6 zakBey~ja{0m7zqa^Tl1$aWanmmUp{LUw+tm<1o3sqib|r_CH-GB6RfNlQy0KJ zId}@0E+5w3wvGikH=J4KY*hjd7IdF3lCGdgqzsxG}`*j!K!p z)T|R|lV-33!bEy0XQl30sSg(F+0<3Kmujt`U{;sjEYYu$tQe%$f>-C>?~s@a{aa z=%5}_X_C)9nu6orV&jaq8S#V!;BGCS2-VwKVvX`9dKkhb8Y0T6P0uK&KgIxTql`I5 z-x=2@qY1p?L#liqm)Lepl4fb>yjNd&P{`w=*OrZl61CQbPe3rlq#i&E!JdVi(Hvosk zT<~RMjn$MbRbijmcWv!(-?G%y?U<4d|D9>+3TU6 zvM@yLXJGkQlxhiRmFJWw2GM9;f$1oXw2D zBPNmMB|_eSZ)-bVPY)*xX3o?I{H#ua>HpMZss$F8MO+AHmZir){cfV~Kdy?n0C6l7 z4%c=^75FIU&ls%gRclqgp=7XLHvIy-;rv=^^vBnzsw8KS#DZyTgo@{#Os`aQmsP{^ z?RX|57Q*hvg75I+>drSZa?x6whvyHax;55tT!f?VZIMgXBk)qIKyY|2B^;ZRgSk6} zsj%N+%iBwBGc?nehbaNW9NGdGr#ZJV*fuEY9+TqI# zw9oPoxcjXxSL!EUH;$VJ69{eJ?7%3C=v zc|V|J5TVz(MR!mHVdf~vO=D8FYOPw%v~fUeu(sHwsX>a+m&oZ1B$lsH%3zX2QkOM} zVMLf&^R5>!LnJl8Kjn297kBNIe@0FO{&KL~Nr0Tx*>{P%o*WwO8Ovz8=xQ z*1E!SwotB@-!20x-s||&tt=^8oi`mmyzHwGUOy6Zasx(f{01Dd0U&=KJ2?s5bGhQz z7`Z7A-{U0JdQrn8a=oAHKAmLJlWS|v6-V8@OQ6}N3}gr{W=MPAfanHn3cR61LKysm zZ*`rcHWnd76I3qhp>D^V=cF6gst$}aRDBA>G)2>_#pmZ%l^#=>V%asQH1Pu=?vKYtpl{`P=QrR(3_G&=ZPH5h#o|{SnexBLdUihIvE?X} zHs41=yh$K&Vv=~TC>R#yf+=KJG!uD%t#eG0DW(Sz16yIVYT@wKtE`dIkGO2s#u&sK zkuWan1mV~sVQ3(Hd-qu9s|sVK+eS(=_>oYfxVNC7nj4>%x*GK))dxn4L7DIB+&C5! zi1Hoc0~wgpWO`38be5%I%d-b1*l91CW9M_Q+iU!5GF0NUnn*nCyPq(U`F^&nJ%4BQ zktBq&2_O#}B9S1mdCJBDV+b9Y7FsfN!6r@dK^da}#6o1*>|4>65^3M8$(Nl)OG|(T z%Dy{1BoYP0R*nkf4~cm82Tl|R^)|Gt#vNpaJ!HC1Vy;puh`8`R{t7dX6jK5VrAifu z#gtwRVM0O`v?8}tGkybFIKzf3k_&zVs#WrF0+*D4`lZssm0pVCVRZnvS zX76e6fY#WtB#V=4H2~NJJ|p0Wdd=$9o7gi}O;5yL9N+k}MlKMF=ND~dd~f5s?$4;Z z?w;48)u^+W!EqKX`H7OOlM1x{Jp2k;$-}`kdu_T z?|2^}RDE$O!orBuQI6x}Ki>6s{tdi-&cg0h@vSGABE<`|)={3!*l)m^|J+yV3yDh~ zdC6y=unI4fQ^J>2Aa9HhFFz^>4s-f%QlCi+LKjiJv`a1)Ty^p%XA#PoZRlyC9OP;G zZD~J3ier3dssvDBz~djEYd_sfrQN-h{Rr4Jag0WqWvmh{Mj_Bee~c(@F#-6E**6) zNmAce6bVNs6JxS2f`Ykvg0X1pX^2RMFwbFYnS+w+2wU0grxe7;qsKrerA^#>o^Xec zyrzUtUI(8|PIQv!``Y`788V2+F>JOHoO3WxK%FU!mi7sKtryo#Lwt2wGrSrH``IT_ zDbE;r5C^%*@JSY@=$Q*$kBkp^(mZMvB;U->t7*h4l5~Dt2;2{==gk;WY_2k4iy*bW zE`D33;mME0^x_b0J=__fYb1sZ{Hrdzq z$Hw`NOmCn!@ss!3FvoqipQB zlXV;)e5PJy_2k!Vx>uPCGJ|xYpHq>Xqvh`OpnP90*2@`s- z&Ffm#vth#}9I!8eaYiOE`mS^{lw#mE=5`o5i3k`YW(*J_wb6P!zr~sBq?8ZRS0%R6 z)dw^WG5J(1zqLdj+p0)OP)M##+YN|)y74l}vDk2&WHL8> zx?$x<70j5OO>(;I5RYyB0hVBZIA^Nb^a|1BsGF~wnyFQ#9pII0J4QJoN1-$Mfi_ov z@gca$c{?eGE^;zwsvGZT$#c~|PlY$GQ})(@Xdy7f~GEqSXuz>*|jR_w6jkqo4A$3Q{+kcbVY6r(e_9N=-*Vg!Kd@ICA2;5CxaS=m;oDKPubOHXY&3l5xiFJ2H?&R!fXQK-a6eHT zGbE4sxI;_fogl$nmke$A1!zw)IbnEJbT6~cUEuRnlr$(xD7xL6W?T!;n24-N_XcbDoU4a_;UfCV2z`PSd73#^s@0dId9ygikhq!b$4zCxj#49S7}JRm zM7iulbMu~^(du&Is0X^*n{+lpwBv*y&({ywC1krp^JYe|O>3?I2{oJblY!%Pjex|b zb21Wa$pe_jDeWTq4dnD(r3JHev=w@^>URATr%+S*(xjHVtNr@7lrmRm(GPSDc;;`2 zxA(`%eXLJbqeiIV+eEDE@U_-TDXrRw<|`1l9*^b+8$`b#DZ>}yO%CekvHc$C7Kc1` z$>E1WMRM240?TXGZU2B+zQIR!%@)DkhYLMcvcksnyZE!^Hb@MHcF1CShQKPmw76kG zlVY5zYA7OxV|Qf5c%n}-C=-4imQ5fHU9)fj75oO{&$>9qLRp<{H6@0Gw__jOw!{4H zCl#WXvX{M$YODNvn!^D8s6(lh%e~x zjHU|gHJ34}bd-jjpVxdO4w?^P^p0=a?N^S31)OMJM~)GaD7eNV{d?zbZeG-3AU#FqSV{>jzu_TChCb5`l)7`#uQ8UOE`k_5bugDD?r8EAt z!6~->)E57dKMFz&^gEMIi(2PJy|_*7q3>U1FPNhg+M0@$=ZYAS4#_G4ZNHFuO#%|D z57HWNRMHVj2=$YwcJ{|jFIy{nS~hoT;t;cl!pfi|8;)#xgu%~6)Vv1jO+`NIV<4a> z!{GPwdfihgd&yl;QuAX#!>$`(t2N(DF-iR-LgNLR*}BFAC81n|{#-^p9#8b~_*KX5 z{go6^sL%{E#~kcxfdD@Gw_{Be461o@zD8Rw-2z+WKZJ4=IM5}vR2rf+HsCvvD?F}D zZU1%!EfjltZ-N&8t0)uuF8NIHLe{yW!uHTkP+^T~CFD?WoZ7wp08wCyEpvV2x-G>= z$5uf#9wWZCOm$2)lUju>)|TSS4)Rvy;`YrW`_3gn(mJsFs94spYR%E zRJwIQ5UkZywZ|L6OwlHl0P1YER>j>H%23H8WWJ+NT^j6oZ^S{uJAq3{jf>oNh^3;m zWCnGb-_Y<*XxO%VIzw_gW+MWD*a;n5LrGoNJeW)SvN3~xp&Xl9HK91BBWNl>CorA` zVKN!*yw8j+E1zGql1@ODsb<*_$`pfvGIXdewl1kTbKAz}P5BIePPFFDAiKLMffzrxG3E02V%!{$+cwT%-<|M(>h&78?e+{1i5eZ9^*1Fth|UD!o}(j&a>4JFSby@$(%lkCMT zvs?A2gh|Mite{@-)S>8<(Xd~W5A0ASFCdoAZp%DXy7h;KiVhHoY=7Pu5e^5^x>D?6 zwf8&3;0B7cE+9Hq)N_4=>(+uLR~wIsh<`+Hs_%ZXblFTV(W+a#kUf=ePVh(|1fF! zIi;APPoFU(_sN7%@-$*Jp6C-Xr_UY3+gC*Hk8B4$I}He~w7F~+PJ$vZvW zE&}&7&Zc(B_(?s_m~uYP-L|29>gkaiFyQCX(XEI zu^}bXB~K`lVUK$$5ni-FSF@!$58?t$F(iQsi`V&Aw;qfqf4}U92nBoDD&(l}lwE7D zjP>mcF)1Z+hV8G#z7-7p|JZx$u(sNEPc*o@TZ5pv1u2q1 z(BhI7idzfC3&DyOw<4uj3xy(;llOi1%zpQL-`+Fl%$$9$bLRZBxUTT5N7hQ#x}W?0 ziOBdWR35KQHAj*bv}3qHef%(SfP68M%y%5comAd^d8@f-=1Q6`D|-Y7rs;Sij7p3| z1dW7!<*vTadi9~s5TtBtJtyzsm9FV&1@cGer>uHil{tgj@|J`0F|FpF+hX3<8ThS( ziGH>}?ctk~(j8UfxtOz1XNgd&+uy>ex7zGvTj;vd+-5ZQgp2N3Udn@oqf^tI9D!N# zO$c=ZY(|@}vGb!#4bo7z%~CoJZrq#)Jk+tL#T`ZT@ssz4-v7!~w;wY0E$k{^yPIkK!nHh@7WN`N<+_?QZMZ?rAM@*!jLV*K{;RD*M+wzRF4NF_g)7!Z^VJ4paHupB&fdM6@Wu1?&)5zg%5s&qc!ix;4^q8oSJM;97D6yS;vP!)BUzNYR#5@OXbfX^n7d?-E-_&6WDHzzD z{PC8WJ-jIn3zA+je&(sH^LhbigyJfW9ZGxEf*?R>LfaPvPhSnV-HA$ zv5Iv>jPEpIZF>&Q1dqOi)DJowyV`-JXqqc%fVA3opxcmpr6M}-E+e%!;c1SVOXN`= zPX;|?$@vFTGXaMyy4Y=bOI|tWIVgBdqChhJam`b)B=Horr07(+$YqtIEUl3W@a#jf_joZ47e~|dLD(_V|5S;~8wijFQdrZ_& z^b9#6)N+uErqxzyOz?K_;K-KL2`vJbN`=46Fj#%68lbsX8rqcyheMKB{f!q6vt}OE^mlrSlLWE?k zWMZ-?eN&58aGeRpVQ5w9rbK`%)!OZNq3g`&FUnuj&m6glu%MF#6SA(WIUP+$iR$Trt865u$4;))_xqmL3sSO6pm_n8+y(E3w%pya;5in&y+NJwI9+htz? zf_CUf&=!z{25HapEGI?K8y8j@Jo-y{c3KzqSZ$1=M3FMWl105z9jKk;KtsMWQwj?9 zn#-d?p}&*NKt=HOT`q6LFvf!}vpKI765BP1{C#mzD)R?%ub#GCf63PXb$YwG$?_;vPg{X(@5)f zkj2lJ>Lg0``%Uu+6PiYH>i~oo(&A7XY6xDs4``z`E9x5>Hi`uK(on9j)l7*%Q_*{1zn2iLLE)1n%C5eMx z+i()~Iyo)k*sXAWq=@5|AbTgbqy0f7v%{OI`|( z1!(vJSGaSBiz1v+Y&W)}P$nB95hp&9VO=!@Wh0JDkOL$Vy&MvFTk`9k$v>r^UUrxK zyqCv*HW?y2LKXh~ri|nAry4pfn~eE`_`8k+=tUeR z6vDm#$iLjxs`w84@s(TiIOpo)*-2Hk9<|hFUvz02Ri_-)`NQ|$<;P+!ylu;_NGpk` zBJGEyl4MA+>}$XO!oFrjV)?v(v9Isce$oC#qx1*im(*MZOZbg@+X+Cra1uf8=4L4R z$?my{4iX5Dr_4huFEPh>)6RZg-~1?b-~HUU&yJG2!PYy5x!uARVs?~;H@5ty z$&XnSQn&CuHiux?DnJ*peK++nKEyf8^~S^Eh)&kGh)cvsk|0)urN4ubR2)imWd7EQ z{zs;ZKFwo^M&|`f3>Fa<($io-YPHNfp>nh;WSp&=%_fm68?{Qk|4Re%D zn8_{V&yiwJUCDi2u^bb1P*B5OA$Fl5*$XsBth{lT*z6fsEQcM+c4%Z%vzoDk zLx9lvgk~kzq@zUExSpN?(!{<%`7*ph*( zPu$r@7lW|I{_E`eVQl3XTWKU!pO`Mcx6pE6uL+piI~)2s_9#*u(c`tC{*>XSLTK^q06<4QhHyzN9eIS5t@lrC6}~hp|XOT0z*CeiZqpis5%X_*Zw{ z$WsJG@wR6q{@ta;ZsI}Hxnej^g=D+JmfhGG*3;I#e8^MUs#yH&FL%SwI6mR31`&3el7YG1AJ=_p&cpK>O`1Jg7e$yBWt}ea8{b*R5 z9q}5+VJ^txC@ZJIGQ1dn3>~M@n=BZ*w|mlJISA`X)5`wlH}FHg|?PF zf!TbDfw<8RiANER*@n!B!NUbqcuCUBV=wM*&Bk~3x$h+XqcFx%>MN+#KjoMNY1r#_&qr)H_zIzg%rKiu~8C z39*SJolY6+s!=gTjnJ#jaSI3;31`)BO``Ge%m zW^TYeFUOG(J@u`A&u^Uf5Hu0L0UOV5h<^j>|7VT~rY`pHQ^x`kLzPBc3b>1^q3@>qC2@s%B{7i@g9}tJBfKU$tIO@2F~6|Q5{fF zFF@yzhP!F2O(SNhdaHh@{4&6w$2d&BgQiBAeI;@BIi-(=hhc&&x3oZieg4kp2J`kLlQjGtj-rf%J|D2KkbuF5pS8JzZ44THg#?%^@ zb-uUi16n9<9cF$(w2W>K)Fj^aw+FPZH%-90cWxK)>U3dwxk?e{)YLe{Vq=0eMic*{ zzrlyq->~lU6f}7v@?Z2f1kG`ii0ZlbRP?WMN52kMNzjeI7s=wNg97d@-CJi7Jd!!j z?H5m3Rk?SZPtnaR2)?HYFFUlMH*VXb-1``5liWH<^P@S9kSg}B3I^zy9?3+*0igbJ z!{B8l{mS_P5SZuMJSZ6YDDCzYcQGYYQLKf|WX9w^X(u-py?HnYO*8pX&M2~@LaAJT zHi2f%u^(6%$&}Y|iLO$)8uQ}n068jX-7!8?DHP?yr-z;3mZ(m!QETAw8?Vdl9%^JZ z?z)LzYycIp|IH7eW->#F>T?Z00^vn)7;$ z!bK7|_3IIaWtLgFVPm@*M`QU_E;2)URF#2T@t2+Kzg7%AZ@He?xl<=BU3q02?+Jz| zvaT}S7fj-X=b+}!n-}X9y@h-lOz@{$1JDgk)SYS zp>TIaVA%~f><$soTb>3L{+mCLW`dBr<6`z6n?E)Ue**;6dcQm;C-X3ShNQm5Dd>2aX#&w7!f#g|=9F`{O z@~ocUKRaJ9XZnX2d@*7-xV!PLJTMa$;GW*Duex-4o|dc2a_!2_vqF3d9}Lu0eK1r*8q6Tl6|IkB)P+(;Kp4e?pCfedC5R9JDHz|Lp|&K`@4yn5nVao zw$tg@Ur8m$^2OvMQd=^G8|yI;7sU2_MJ5}o${jieiSc(&d?Po-d;(8$YUxIn z<*hL)Nqh(1jA=B$PMaaNsIj60idbR%X<4@TM9>+CvOMPyf#OwRJT!1#q4Zoej!XwX z#IWUPx2fsg*DaVdTP95zN6YEQ@!(8gv10br?GKMr^PlqS8cBWo_1w8O8&%lP$HqMq z$U!JZF<&?m@SydF?uACBMXj`gZt;uO5rWwPR9p)5!ZH%Kcm7f^HxLe1a1!y#n0VcG zMDL~XHOYsqo?MMtUE5X=u2q;dS^3Tbt!5pg$$(p~k)l6^VeC$s63xV#1Lwj9OAr{E zWlfsFBz0!|Qu~JHlLwbvE0x~5Z>v8^qe_tUc{`0{@Px^jQaKA!p7<>*`k>7nO;FAR zpH!%-iO11)N@j9WR(~vMD3;L|koE=3ochNd!U0Bc`Oz86iDO7Xqkwlyf_MA(~)Z z)SUEBfrIpfz0BVLULTmBvWM*m`_^T+1Wt>&_BL|8Hx-X)x9E#;r>%p4$!|cL+UA!m zdLjuo|Bk4)e0*^JpM^@h!@8qiV~UZY1)VDGL3Ruuowj!(QIfmrPJ|q1r1t!`A5y1; zPo7u;@b~h!5=lb1eC$P_cgM?ILA0)wa|qp>yK0zgoal-Hdr|vnt57EjbTs*5g}yDU z+;S=9EvY`b)B*H>(t92kz_i*g*ge2T?lq$Q;f^_2V-@tQ;*BBWk?gIaFc&eqPzcyr zGUEv%V~`{1%n|53h_T=9&lHDqax&KwFNCL-+VCN{T3k}8d0h9m=$vQ%ssa%HFuZZ8 zn#{iSxa7@nmI0{pq)L*;>%fD30s+*Eq`wToV({WBN~HvW%e*&MnqP>EQ}v2|<-p-* ze5+0A-mtQsk4t)!+u_N6(o2?r^;e-96G4qG1m<4J4f{*nU_(jqx`OhJTlq*IbtZ#? za8LKOMeE11HM;?MUQjt?782s)oG(4i1tTvZd+TJ^Kw|!JT=T_zqgfL^|JGNiB?BOq zS`a`H8w*&8QjsKbQ}QxWne{15mFN=DjeoGn7sr_kvahG!vZAEsm@9K4oE2mT*I*)T z8gun@8^)p&xBvq%QU`Ya$#U74Ml3d6XjFYih@ALOVmue+%0Zz~lD0u@LBGOMp(Xl`8 z0&e0GJYzfz+;=xKdv4E@)ZYLVJ3_uwRqJ8aVY;~fm5AEKMMx!{s79UZ2@kRAWSmw~ zZi*5Lqs^uBp4WNusvhs%hKo%%qc|f!K~pDM-YNy%rne1+=9xuxa&xRv-yYMJ!r6O7 z_PuhN&j%&&H4O-?FqD2=9V(zEWY_MsPLE5$Ry;@jUSpU5a7^^lbMnK}bUTY@K72on zuo(gQxxY%1F24b}yT9a>r<|vXM3Q+?OiXPLO(Z<%v6`E)_>$zL-szehqM_8SWY=@ZSaw)}$i& zr8_j!nxup{$K=drRrjT#;aQ$#KAQn5MS4&ObG{BkpM7;0SG*`!b*iLF7pZfQ@6Wh4 zagR#GGBF{Na$(=@Y_$EdxFTP-va#uW#3hkqrT?qim|6tTH+q{Mq1v;38b@89Lvr-Q z*r>t9P}30D#Exlkha$uLH)y)?k=kXVZNCBH>drPp&{aAv5!YTi{vjCQr#L06 zGE@X`{g$U5KjP(*C7;6BGl7EK0A}*nbU^h*B|f%%|8SX4C0)R|#cfcN0@)~grL`5< zxf7?qn{j+K3D#LvQ=R9p1K)qSKNf3!^sZR7+c3zn(&XXNZvf!~r$%vWy^h2}Wp`*r z;$m2xg<+^eD;t&V&u40G;Nca$yfHIN0@5IDaT5S{q(eKRlH<5p&eaGAbS4m^nF^Ch z(x;L36Y-N)B_b)*+7&D34k+k#ppCrYTuV)RfP*smv4AizLUovcDmC_zE|i?Ay?)YZ ztSa31!C~*6O?g{B2M9WiG50czU`_IXzX3(fI`Q?@4?aKE81J+;o zK!Rhx^^V$=xCY&iWhK}sWB$brsEy4IUxHG3btGM@GH zA&k(!2Gg>*Df(x#5# z6mtc`GCrC;VsR;5Mej}I8Av=9jNed9mrhW*G2*`yp^Om3LOzJ4aq^}l)_p1%9VB4DPwvb^I(9M?6y_=}hTwA2GA zdrpil%VKJmp~7y(vvOZ<+-$f=IN#a~_~C1mJ(F2ZPeDWFaON*8`z` zqFZp2=8=iNtdtZcJo44^Y^|A$H}eB7ch;uBOP1_%jTL~dlhVGs4^3<^kq+F>bg9j| zG4fuTi7Ltz3vO?(Zri*?DD%st(b7L#U8fv_IKPUXutEzyJMSE#?1_uNWoAe_S=glb z>*_Zk;i4<#Yz-^+vL62HL=&sZ&9$c~wDfWBSzStQKMlSx7o9v_P3&Ml*$y=ZOk8W{<6<;HBGqmN*XH`p<1wFyU=UG>A*=4c{j-NSKC?K9>~uB*(5Em?S4ej zy;l%Pg~!I5SO#D^JyuhWWn(BuR66VV6Vgg()QU_*8hI_B1wr!yy-`Ez3R!H#mITtx zd$iki$NJ83=H!X;c!UR7;kU?eh zYe-GBr}7`5DZH0h(3Bg5`DJjGyz&K@o$u1{VJ3MTpEk~9nH#|YQgf?{J=>=mBw*mH<40rN8tb1OXAfSM34oBJJLLzQN#N6v&;K-A zBKoe3ZvFjl!0no`8yiCzrlXkPiaidGS{&J!8K+_vr3 zic0@9ue?jZ&Y9cUXHWd&&a1Hhyn{i=h}mZd%1w;EH=y_~Q*YHp3HWTzs!AfFpgo02 zA29W0|0n7{cS=3^vGlSQ=&8@i5@;;q_Na19#z^v7~t$ z+UGklBz(yj3QOXf#x_T2Oy@-8$y%8Wdssj5KY1yCc4f?sR_mz)x9 z8GbESIVWX2XWCvWtE;`Qf(>bdyUa|4)1zt43QNZO$-+yu#5 zzuaAeNwx4^hwW&+lsQ5Bm;LW@LefC1b)<}Qk~z0CPB(QQ$J5|FtOi>G3eNX!6^m8< zn=t%@Y4z)T;emb7qu48@;sQ<8!&pzNB4YOH`8FkLd81mNC!GFe_gB8C>}a)gY(!yF zJp+32kgW52(L^BW+DUv$*#F0y(`Vk{A5~UBXV@zn^7B$d6?rDwGn?~ASM)QxjXGdB z@^>mX|82}XPziRPvE-UIA?UI1`<$0kUVOv9nQ?oinRz;RWy0F0aS$~4iza#Ik@DJ~ zSVz5$*%ehfG;b;b&qwz~{DL2q{YWCcJzUJSJQp67NUo8%a_0k{;Ok4y7jrF%>`Nhh z?D^ko2_!f33=F$TYa`#{2;XC;cQGcxN^C45so&k)kD&SRyzVDwcf+j}y~|R>kwgIc z;tvtxiP7Hx$?-k%017ycAG5fcopCh)E3Q$PuxYH23kyPEjTQg@KmS)R0SoxPR8ebS zM}4KsG$-Rv?~!)}%tgNvE`J*QtEI!=#GbdV|B$W?$!rAIcL+(Ms@OB?^ESkWz@iLs z`TiUHP#;g*t6#VLJCA>S`XyQt`doqi$nAQ4f~lY;9CJ@eCnL1t*OT7>xcjdaS(G^U zkyKdE5B-1sbX64nF)3RRe4=&5T`9Gu56VNqc_OXbxKWa9TAZoSic4H;BQ*V6fF4|0 zEoXzoPpjJa2aX7Ej?^xaZ;-V_?+bo=8BFjgAcx)~PPB)1>wmvfN(j>-Q-9s{GpM2vta8jtXb#qxahWRIpY3+*iKVerpd@ zG-jikuuE++iN<`~yaXT~51Zfo{ta^Nb=BO3A_i2~)Fbdi#geh* zDO*XXh$fvh#`lm)-X`d2V7N;YZ=Tn0fcL123F9X*LteFQVn=2T5df|?+xHlB&2XkB zxt4f*5A+~~(OP#gTk=jiK^#F;{qx#Z{9KV^pww|qK~vVKXe>SSAwqULy`-Rjf%r+G z;5{|h&9??BCJI9Q9De#Lg0+h+CEGZ4SBiQY`oOIltO6(6-4}xui3A|UH--fkvG0UJbjYE z{ax?J*Po%XnRXi1!^b4z z$Xpm!=lRfDO9otruGv2CvXRQ^%;jC+01{*hWQmn$^1ZD<;r4MevfUVgVTKoWizBj= z72~TfVQ3y4z#fGB52Ab1pr<5q@&L4EpRDJy=}nEPs-mh0NdfAr)C(aOo!o2p-ujb10qP zTaG^?k^x|5cf+yG$PKnxtrJJ4j<= z%n4;6xBDEKNc4^zRKsG++v_Lq??Xyp%0u60B-n%RC685nJAC|=q$&5?3~@P-UlmNQ z#>rxYwG{u7uR{6EDBrXx_O^VEq#&e*jlL3!&AQr)MTUyJkqSv?uMy5Q1+wV?;?4%$ zAbQJ?j0he}DUL!%dOGMk9O{uoW)1a#Zk$ik5+hl`@Pmoxu^rXL#z{KGCp7^C$wzkY zO&_I^l&U3-IjjMa!mf1=d@wfrWSn()Oe{oChXB;a*OD0V3W`QkQ|X*&Eq`~7_B1+9 zpo)A%InMez#b&I#IhLQBR6WmGJy&oZKd0CipP?rg`RU-gOZ_@RN`9{hE4+T|=Hz>b z=#2xFf}rh(+e*QIGV>2aJDF}QtHxP{=J@)GMeZc3JIrJ;=n(y!k}}}i)~s6lDwxH> z-Wv;G+v198@&(@beHZ33+A^&-@oe`Z{iK+#E&iGx7l)AM1wULbe?D=P5kJA3#2Pf# zCVrSE3IR+O^*@M^E913de*c37AJXIWoOJad^BS{fuzZ$_O=QqV%4QC30-!MKI8FIFEJ{$&*tjh zGsu1ctl({mU1R=Lw#(N4Z|I)u8%K)9NmdhXIiu?*33&Z7oP{*dP6~&E6W7#?dkuv@ z-VZX!=NTm_0PtC-c{PoZ5LfnG4^s%+)NY zE3)xL3AZ&G4QWa;lgyKyga$39Cpf$WD7 z51Ri*=rEXT%It&RG=_cFH@#P#Ed01r7FU=P zB#@*rYA@%bav8!lNMed>MmEHp4PD+xLpW=<)LkO5TYQ zj5_n6bSy>HO^tWDhsRcJ!5D`gX@&*xgib;rpJX7KNuob~%kQ?cxXlgbo^pZCYyI0| zJjbsCryk{XLgI|1>BJBtD7HHe!1$;nY1i*AHW@5)mB^!bmxp4sG9t8ThM?!)N<9In zA)2o1sd`PNzQEIhyg5R%QO_K(HN1s8xTZ*HJ#Mpd$O8ZIW6bzG zSs-bmV;@)e@LC^B^S~zZQ4{@fZdN(mdJJJg*1oK zJRkL^OAcM?4ZEZHLZ&Syk4z*o_dBVu&ZCCZE@W{UDmAHfSW6I3bvF$`xF)eFfTCQ4 zrU^8cvNDZWvFk*N#UsL#-wsvV~m%@Z#+ImJtAx5TOPxaN1@wb>K- z*O=;P5En0D*vmZaN|}+F=HFGlVz?G{O4Hk2?mqU)USxC9umlls_3Pm1$Tz74;-5Cx zJP0u=Xn(~~%dhF(d^PgUzsQK2eI%Xic~e=fqfzs@orQU``Yw@mvVqmBoE!yyKM_k~ zYKS`1t1xU{t$Oxe)tP$HA8{tvN%wC+&_8NYH&%PNKOSZiG(K@n#yy@vLWWm)P`JJM z0uixV0*(7fb8B-ieiB?Eo_k@Ga5ak_PL)2!!Q^|*)CGkhRnBgRU@HG%WIl0251y~V zg5L&Zs~mE4m*h=0sAr?RW2MWcZp+%9%!V#Oy;$k;S&#G)V&IGfPl7yk?jk(x8{zIhY{eiOQLb9il#1VYo~bE#9*pF&himlzGgZW7ssG$9c}sD-N(mNa=-ls8e62=7(bes zbl-fWIJUQg*edm%jC!3omy1m3J(A{nJa+@?N10EfjvVAbIOX$`dHwS-v&U7^rVhr= zah-;4q7r)^>HFL&0AmEv(%U|9Q#oWisxJ7=xaEt24!9hHaylQJQM4`M;XLe5@cRq? zy7C#b=@yxJ{gLH@np=B!UWQr(V{%r?&IXd0I_>tJ9qbdB{j$q>K8j=9Ux@v{PK}+rt`oAGK1a8 zs7kTDi&D5(=SE)WgT9Xp9rUTYN9OTI@wvXx6IEsgXS|Wb3U^p^raeOYFq5Z zNs%g&CxB}@K<1%K6Zy~AZXhY6eil_mJ)mlRBr^j%?#p3tV_0(T(Z!IKgAhJ49Hout z|B>Bo<X%VEkE3C|szT98b?O%0_T5hkXAX;^&w_oqMU8qM z>R^~?B$xVqDNZbB){D=y|HFM?^}I0&o6T$4z~K?BtZ5cY=LfM!qQ^iYmOa;eI?~)~8In=0DVO5$ z_+_QM^tpVS|3QmUVtTv3HpZ?0ZAZ5~@uF*x@yHTnXO6u7MU9y2MkJz3<2_VDUXmDS zKS6*8a2r$n=;3Io5A{M1n7bC&qZl7#`Ff`8j&*8J$Z2R7cXPHzJ?l75%Tczk)rm96 z%ngX#hJ0GolswrOkb79Uyga3aL4#OYsPy#slk|(^l;#A~zKz(Cf*F)9*!HEng*5HV zj9~p9yM@&fdWz2GBh5BhnSgi+czzbOkK*_C3(3Q@kOoAz*_%Ol?GCM!nZAkSw=AX^ zc2_*+UFt)8qfC-zn+ll+1BrFn63=n^Lw0Czjy0~cP{6?Z-9A8g92s2w5OV8%B)M4m z{6ee#ec(84iQ{SaGk< zD(&f*iPTDToCB0*wz%9yR(MW|coxniV@Y>>TqNogX0|rPM)|r_r!O4K35H^%6*_3g zbm~KbbxJyEx{i{cgl06@sEe20pPmLQZ70`F<~?Y)qjZqirCn%Or=%A2W0M;i9vyi= zXxc<_IGP6>>p*8Ys1RNAMc%yOZC@s)ddDUS29bnnC(hOYH{~&8)NC06rF`_K-11NW z-2&kf8ST-ty}-{>rrKPRraM#&VOg<7ayt42s)|WuURd1~p$6JT1u5P(r=2+G!NX0< zJSsYni2!?ggJ(oxMMlW-6Nr#3R3Z!jZ)ug7?Rad*0R}^8D1K*a#qx7 zm+{^|u6a(hg6hZMhEgUZ^6hU{J4eK+#fZ@vy0~?rls;p6GT>6aPi8M}8H1J9Y@143 zE#EUPnCq+i__ei%qtB30Qk`e~Irjm{y{RHz`7$>GhckDU13Z#hlDc|U? zVW22kFk&#+v3R2bN1}!zg|9ws@1CMk0Pvx>4>)Wj`2MnU1uz$O%E}#w zxNz2~p&OIZnlZ!w-qx7l$q99&4SvIMkLYtHoR?fjXNVW>Wx?>h{IM)#>o9#OKI|I* zyO>1>*8VDl0l(C=VPaHTaOah2PKT`(hG`f77u2TM2$c+TQB&$A8-BefU0X=UbB- zwYtp1aQLfr=oQrgsbB0$g=I=*p3-2n_JmENOMOz0!bRI5{#_(wnfKIslZU%g`+W(% zFsJx;#o_H*;y&2YQxeW34GlUG2o`nB_8-PsH^q;YP_P;I{v`4jJ{VVcjay`9B6ANB zthECpv${XC5N$BzBF6Gz?djrju#-#Uvhfw9vcP;YT>Sgp!$3@R;Rv!wmrN{wZ26_4 z?>_%ZWrG>}hEwXX_dSjaBDe1|MzBWB+piT=rTto&yy_t0mOhC(TnS=peRvw)(&J1uFU(26*&elsT=t$Xr7ItQ6yK}p zKYUoqfEFr5$rx3F1azyNEx^W4^1&V|ej^ARUWlev4=y*i>=gcU@@f0|8n=5|)^0Vp zDT7z4Dh&g8#8Cz&jGIUOXZoP)qS{;~d2{QN4|x3W>K_%W+c%)`A?dK<^q_!FaMpsnIW)ccfw=4h`Kv2sy^$K6J$nGZHzfv!EW zea2(5@LN7r)=*@P!D4+#A`_ER?b|nrb*(H9-^!Hl2j7<>302SScT!$K1~d5r<|4VXuieY0@;Zqe z*ZB$Ls#nOFO^o|w#_h-R7E4VvG8H09!>s<1xIEk0m?fx&Y)|)wFIzr-%VC{*%x*l%#d;UEdOtN!z-M(W%)Qc^ zYo6ohUB82&kuys|NYnX&+ZYS`&HxFzw1V91kl@{Nv+}EQMM1AP*&3Hvp(+x{^PNRy za#aMdjk-atPp0)*nv5V}6HAsm{ZOvu)gtcha6un)Bt##VD_p!`r9`lxS5R#_==00j z7tFM?9_^B4!X_-vco*|X@=3%?Ir*SIcwzS)-;k7KDvh4h z{92$TfP;L*EfhYy@zQOd05QsYtmC$ z_L@^p(boH8g|Z_0&UETk&ad8+G)JCj^||wzn@S7E-LI|AmG7@@Mw7)yahEb<1L6*? zP1GH)U-4sOYEg^aFEMkkkfUIi;vL?zWs=ksVXr0bw@b~oBZ2CbnQkI<0WuCP0R1fK zMs2*rj}+nthe=R#2Bj^pU6U;Rn1r%sV(SG1{{@JPHpQSS+i|?WjC}Uw-0TPES)EP) z?B|jdd?aW+R1%_Go7ed$f%=)N@?P#r5-#N86fv5KL#z_nFc+Hb9*5>gA8hNsIR#om!o7$3^Bt(BY zTH*KRmD>YaNIedJVSr}+=;EE_&X@KTRx!O#!cm^AHONK{an2M27Vp#0-1ZC+&@sFv zSAg{bMmon1npLXIFfPVPLsS6`FYkIEzx~TuXDK=*a2^J>vhId#bDfq&V(qdAy??d+ zJ&lfaI-U91{!k3dM1F7;b(#0y;%j6die2BgK74zowC49mo%z4Kh~1n)I6t~=Y<0!? z)fBrwpk!q=uCd9ENZyIaAb96`9pN@{RpqD>+bk!;-tZsWyreOW% zunlS!=O9pnZp{bFJb01KTZ>!D%LOS8)SC2b^;$&*G+2IO@v7*Ph#AH8l5~dYPrDeB zs7k2^63Y1mJy8+$JJ9N#^OhBG6Mrd~>u#xxKz~ZYimOHG_%ry#&}dM+_4?VnfUeJ< z8h6jduUNX$3Y!8y%EY5nz%b+E_B%$>qY}gt_rHO(7}zM?6l}xJKWk#rFEiwFNa|E? zwWf+&f_D;+a+7PUDu)FU$x_vM?Sa+-gnsMKI;w{d3xXF_1`qf5u|R2=S;2ckL7g}h z;~$;1waQHjr%VO&na^n7g720abMuO^(5&Vgd=pgD1romI9I+CvsR*Fo{nXN^Er%lR z^l%$sV&8eAS1w7{h!!e(ARD;n>HJ=&g20bNFPWH_zLjjBEoA7w`v#6+`ZJ^Rd<8{u z6cYD`S;@D@R*&xH9MSVXVm(<%gC&e|dK0cBE-zsL(@3+|4w+TEPJbJ3%k6;F zh+8LCL)CExDD78qR4xvPmp;1NaLGBefOvN%po(EN6iz6Ng*d%N_pt0or=+m#qO7r9 za?%d|Q&aGK1gyT4Fn&nf#`@@#C31@(dNW>+Ps1n6EkZqUjUEoBT&|sq1|64 z_gV&`nR5}X5%M8r0l4L2=tWphdp~h%+ZpAPhYcU^KHCZSE^7KRp5;{(4J_sV zwmN)&2Qc|yK_oYm+j43fNlM33x&w^`kfAU@<^g=Qy)m4k<*A1Ir!s88g5J7|H&dAO zTzaz5{6MaV2O{G2bLzqltxI`H#!Q?k1_spEb)Q%_1?Fdj-EK7tjq>)2g% zSfn95_Pt^1E5w#fv6x0udL93?82Z3i#mapJSG&ekLZL!S4<|_;0sk$Ok6;081=U6~ zwaC82Rcn4fx0b@NRb#)cDz}peD}d#$SfL`8+Lg$(HJR)T(t4m#F4<-()G<(NQf*3l z3uVIV*TZAaM*OJnnoIxLuHx;{Pg{3!c_a$*yfXK3?d|E{z^tGED={|Bn}&v#hYdfX zSS#cu8TiOXA&056ihg(Cj_fxDD>fK)XV%ODH?E8_;m4C6{O8gWm}`kjGDq=&@JM2M zQkJa%_2ExoZ!5#(^8(#UCmH=t?=0wtzD}ptEBox6cN5WkbI}^Y9 z}TzmJ( zS->5%g`*#YQ;1 zZuD8t&IE~P()D_GPcW|%Z-0kcIprsn=0a*bn#GBtNdPJG<75t#-T_e1#68yV@l2#l z9%QoM62+K!^B(85`yn~)VSO?pWLvj3G>)^YfHF5+#vXSq4;un2tDB8#3}lDVrXl@@ z$q~oo6=4^)pGzzsG14y~aQNL5kB#sw#5bv&@7;R-H@BI8Q?~jgSasvOW{)+jn>xe$ zDjj@%GEH_sb2RW4E@&_#py0FS@U6My4`$SxkAJY>8SJ`CPH%q=zk5w36+9;s!+-d7 znGw=D_}NWgEow&0LM5n=K&HAfI;acIIQcgt=YM3NNcMqp@j%v^^(i`g0RW9# za(XPM4vy>8@egDEv}nAS{K1SG*8ga?sZud9u_w8!_ za~;rwE3-w6!v(Xq=S8S;!hbulKL-h+h(LOK6^S~)zqh$H{KL2kzf4>GQQ`4y_kR{m zmi%>H{#@0+wuItP#CZP)UC7HUFUza^xv*A>|E0cI*BU8L zp3QElwyb~IrSAr^<5x=>TD6an^B~2w_hKt(H()4%0GTw*^`UAtNb%kc8G-6 zNuwh$66hih8uzmNSv`B3&W|-_%ZCRVra$08mDHZ9`c;;uTA6=KnrL7}tN1cM@qelb z-EJyxZ@l8hD0hQ+s5$fhRA2vtGg4nF^5zN`2GxK{qn#-=Fg*74Bpv^}7~eJa=~-+t z`+g2LMBNt}xJSHia!hFp3#|E0Bnnc1-NfV|IY8mPqnI?L^2W}Nw(fIZ|I@Mx!*=;# zqv@&@_BYl4yPQy(9>B-5!7ae;I!Z^p0;6DgSNKm@dS5jL-C4cO@-w&;@GVMt6q)@ z(bVh{w(=>MvQhR;Xc_w|^{hc`^6RLHGfs<8ihpQ2+oR?q{?--Bcy zbY`7LJU0-0JFgsWXnP0bDUX!T69_AFl;c8Too{p6{|!B0&c&|uETJH8%vjK%lmcN< z?2XF@eD+;!qC9i=jBr~Sj}%+A32EHYmpBK-A*gOpKauT&zo zxXqG1NEQE|{)KSUG4;;lbOBsxoXSzAZ^x-j{U7YTXH=8hzV;n@M|zRoLJ^P}n)D8# z1tMJ`bO^mEMd?B)0-*#5AiX0^svy0DB25fUiWE_bf}p6l-mJC8`<%7++H0SE#yDp` z<9XjFA2RaczLPr{cjo-h`M<8;bwn~WBed&3n1R0yiV9d940`Id@}}bNRkQ^is7NvK z-$EDOMkk%Td-!;9?|%iIe>+XPSbrE#bn$|wj=z8+vsD4%Kfy-UNI>bF`N_(uWZQYQhNTaX_=0+AzrB3m=_o?EF&aExqJ>S|FF`o55bE5Ct z_ys`uA{o~y`}Rmd@(WFIk6g{)w_hrc_P7iU3v++E6@1-u>lo?W4Y(KJ+LvPYpz>39 z2!?}?=H_dfc((2dL`-#Y08Rq6eZDs1#s^lKBLrpjkTi!fUu5D2kF^=>oH| z+tynJtv#$G#Uz*rsz;NGbXi1&rx&Jt(}HvMT6@6;&1AbjwyfHEIe^%lMjmRttbAEu zxEvKljwm2g(`_Z~%k9#BD~rElCT&+m-T&<<+ip(P*w^*Ap%0a|vpz6=IeXC+D}cCI6<(|5ji3`HtUNwxGNGWpmPoFHSOd*J?o^zXR2|S3k#U z7}*F(BeIwk?1~L62z!g&-;=c~EvyF~t%6NNm2NkX*CBE|G#{;~i6TX-^ZYWTRONBVKFa?cSM~dEU@TkoO1#iziKjn4$b~fEEr3Si+CN%0 zb>wqE5w-W=rn4Zd(!pw?QxL5 zaKTg!EBfP1`U8s;7y}g&AHA$hJk%ozc>U7dTVU@<7venS$4Ms04M8}FBJ-s^+)0JXw*_j?}0JcOX<$%D&YTbPB5^&QQQ{v^$I^k zQtQpDAv6p6=u6`rhY3f_^{-(!%~3*maR^5GL{eX>5*H59()TWL;*Nb@BnnD}az?Ut za%yAXs(1drcbnN~k(i8#aj*bE<)YYw_J4aNwta^lW9aSe5>WFC00_9~4}8Z)?EY%w ze?vLwx1C*EAY-Ia?k|CFMV&F}^YYd|^i%)lvUtcm+xxPRI;1|o8);-~u()b1C+HJU z9*%BrKEjb@|DbfJ&8BZmV&Wj8cjMewfP}<8E?_CV_yzFQ^qtchv0fyVsyGd&Q0cp z(}XuGpSQGU5(}UCnHe95S9^;5$Pv%fC{E0g3O6#{T&6QJu4wUR$e=UbBw7)D4X-is zx9B_s3w~g3R9?O_AzkZ%Y^NvF!>oZ^FI9h#c0o{*EMEgw#Cg@``MmMMa*(2ka{>f< zfiQhl=(ymhw3t)WDvXBq*$Klj$73|~JDWk%^BWeG-sxnq>suC#64Z1Lj9T|UjM(en z4&qxOtE-HOF%*{YIbltW*d(Kd^AfRtbIhjPa9UQ%8@fG`+fl91l(RTUGzcBRqil3& z-&;OfOO2_75fuk=1V5G!!_VjO*Q*#MTa!VNNc#F({{kpJr}lpvvV#$YVM`(2!(Mr+v=wxjwyO;af(_Q)>tK_htPK2=4BrWyoytaqxN! z>L_Y0#H9o!RgtkA&>Pc9&I8f>PUS}OdSiO|ei{GA9tJ~a8IU)#M$fApeofdWcrin1 z@=)`~gDUBx;9JTOr3n;=i1cg4eyZZ)l`u#ktJG#2b#eLUiLo`Zd1D;Qzw5qIh(hBU;07}v!u zka%BortvR|3o(NA{aEeWK6=f7Ff4+PaT)8JQo?Ywc0@ z(UVe2+;LLKHk=D8G4l*Y(?soR1_^K{9>;}7@jRK{Ygsmxw`!POy^(#ZrR+)kNcqqb zX`@D{QmI0+xRk4*XBT@9!|A=p9nDloj*ma<4N>_`6^QdK(lRX_ha5R=RSoA!#2((8 zb`&}Mm8^($nF@O;c31vEud`5lJnC`5$~=7@gbH1VJu z5baZ)nAje9Fjn*HP<+ko4~EB|bs|^H=v%w`E7U4*Sm^36fUO+DQ5s=Qy|J@wwTBfMIYlpE$gq7n~W~qSQ%fiYiA!XQGn&$%I$kz-JD-I8$i5Fy`ra$Kl zyuRH;=1lFL5wVGitz{D-{C%oDc#dWZnp8@IvX?ny^&x5W3=1Kf0-R09rOrRCts$*U zq7zvmE%bz0e31Q_lBgviR}N)&^#$l$z$*>>r0Tq8MvXK-8k%|bZ3<%`4pA&pYe6rK zV-yQLdB;uGh6;NVn-sM4yi5Q|_=vn(KA$^3>9N%ay&boe`FX0Ca%7ancq@v(`Q!OV zoFrq0v+U=?MddsHc=zV-JM~}t{?%S^k@au-sBg0^N^Wo*xp8v{M{ZQGB|!?paO6hr z^lE=fdk2I^!CoV)5-&c9K7@=Khi+8+-CFft{0e7GgA=t#J;)iDD>OGZ!vWBj0!q>) zF36vF9F9)g3UGx?Jw+|Fls&vuq((A=?+j$qUZI|pSCsGd@Vz>+6}^0(WyhQHJc)Y8 zGDw6WFup@M{o<*Z{xm&5_CU97zS3{>&d0ipQN|7tE;3SkF*>HT5fZ zCIl0~dg%lic7$bFjNN=JtJ{jc3^87FbVnIP72GS%S2B% z@w(aH=4)t4wt==fiMWM>CDU|00G}P<03~kA<8L zZD05S`!^@2K?`r1h*=Mwdv#Ea1M!F_i3~fl4tVUhIZor?_hg>;W@QTx*PKc-T(2a{ zFa=9yZA12YkBXZaQ*C~NN4-@v$|4G&XnrX5Y&nRVP%DgbUt&%1D)CNJtuw?XvlRUz zr04uiJMS2m5#4526x^0UI>gCkJx#EYlA*k@j$bDKle$K5k({?4j%99_D8hzX0By4F>i(PG%LIvDU5k1x4A#bO=1U zG3QD(?lxt&!dqBVF`po`IDSJkf?gEmUBRp{k*e7+$1+M!nwU5okGwA8)Dr1-GaIos zWj`-8$-*BPv`eH>u+U~}>=j)46bW{p;9!_Lk}7xQX6e$& z<$9^sbgN>tpgF&JP^KExTwH>3jPgS4WGyLJapCx0*}7b?D0im2^djCMf}o0p&5(9CvW#g1tVYlWOYzeBjjf1}!*ex)e*SnzKr_>hP zu4*_?luFGt!5Ze+Gm?oLDJ3$iB}wG3V*~A9dQ5P=>CTJ_zv*<7=&@8#I}PU}1;1kX zEc|U|u`h40_!b$a0r4_%{y(v-0AUB~`|-s4m;!UodLt_+aFs-&lF_WGy0<02XUWEMnPzP)HM#)sdOeVg05 zO@vW(HzsB%H;*mNlm%(@)abcSJZ2@PhgbCZE7f&{1VFIvm~Pa?0G_0_*7PHwq83%r z5QEMb&nvez-oyhgLNFgKOd&3U0j7WkEwSLwVvnff7 zsjNy5#Sj?MUx`G_hJW2J_=<&Q1i=0lKG!TDD4N|~054I_1v>5}O=;O|YE?p^ACJ2) zV^xaXJ@O5m4LrfzMSm$28l73R5!Lj0S=ZD%*rS99FK)QR};4;nKR7*eO&YW`QjM_egPnP)d?J^ zJJY^~x>D6G6SkXxeA>au&3A=fU5YKxfyH_`(967fwcGQ88_9B46u3%P5wx{1okbL?x{cFT7cv1ZMNWhLGGIY}EH4O(p!RTutSRis+Xbo^JR@r_K_&EP0an zg2|*<97}V9j=Wae1n~+!53}a;uzByQ{gX#1Ta%=T;%?Yw+g(}0!51#No$8+XcY^FE zv|-td0NwdT-VXLnUTz027*4rS_;6nGLX~%I(f8T?cCiyUYI|ZgJhubJ^b0_DA3LIt z<#v>l9BH(o>%4O*w#2sewN&5qsbHBvTZx5V+=z(@2{nUI0re|^DS+wcCR+J@_K-RH z{7g*)v$mZiB1YmV!MGsZ;{}sts(Oo0wz5OpFBv!|WIksz8p-B?+*@U%EF{%N6)Z$x z__p~wG(u@U!{%bO`LJZPp_^ABlK8Y@iDy8$VFp16wMM!Dw} zkcrO?WMa0!`)#g9^XAtzyzFX$e8qUN+GpRm_OCS2_qMuDy%;)#R<&q{o=MfgB<}Qc z3I4NP?U`Tmnf|jb9YzweDyAaD`S^#CzlA4_&Qe)U**-@2@1^BD)P~hY56|aMqmX zG8L8Ig{BJ+{a8gIeQxE{40<_qEf{71vHN0gx3P zMC5@|c%P`b*;fbLUASvQO!G}Zs@gE&spedM?KOtj09rR~HncR+7jC|zeS`;@^TDp1 zj7ByzByE<*Btyl{up7LJ%o&v+(|y`oiHoPO8S#8meZ#(VYI8W1);TeCm^@Ewwd7@Y z-w$H}yQRI+)qMFpr*Y?&`-VPZiLalv4ZrJQJIvosPFM8{^)!5y&Hu4sNmWaTWt0-{ z%5ID5LJ?^Z$O5>O}sy&3)(QlRsy3%%dy zlC(LJHdIlpIFL~A;0@17ny^w6J$3VL`#u3kKQI=dR2IdWys zQqnl~e09$UoJ!Gt(GIz!75e;Ky^7?nOyo~9*}*J}%iC%L7sCFW{6|u$7Xws)IzSK_ zP4UN@REf)t*9pLpyOPV90dJ!F#W1rj?s?1C)3T!1zb!v~Bx6`Uf659HGvf;~01k6& z#K&waMjHH;@&6yRR@8luKo1qzcpf^*pYbFkq`j{`LG?3+r8O+iS~lM^3a7`_oP_J?;WI0wa&lsC(x$brVpL-%M^(Ixd5gaH7B;#_ zKKYWrML)W7K|hH`!PGadC+-spe_!H+gdP6r7XV|!sm@ETPc|F;mc^g=7rw$WzWAzS z)x$Y>3ZId*_s)~O8khua)wBaT!LiUo@TP^=eaQ2kt+L%BuLzCWn+iee<~Z3 zDbqQ2Y1Piqf-(`AlHgYg2X1!mbIN0zpW(NhO^9YXc(l#Kw5ToEw#2t?xdOVTlm^DQ zf^#psSioEUm3e$$>@DOBqOfhOYYSnSVFYWfIJYI?#8-R4kvOg08 z@{o5vm`F4O>GKvVB&;qEg2a|rAfe{HkLlHSn$Jd$(!49pVE`+AxRoRfkIgqk<2w`R z$?ZG$1v0@@pnR}iG$uAeU`;TkpIPD2J^3rLq03!9u<_l%;7?LBSpJ$rlDWizd&}~| z@56L?h+HUkLy#JLS%%c$J{67t58&hC-lVZ8f$=P;W-zyHko0(nB zoW)1;vX;dkye>5rf8$yysx8|}K9Q9ApwsP5%tDVOBrfX^(f_`5S75bEa^rXmKXG#n zP00l4u5jxiX}*o10cCJ`@yKvL=3u!k}c{jBu}FH&mh#WQBBFi&u!?8$?C7 z_*_Vn?Y4=yQM**j%|Seud=E9<78Y?1(1@VQhG?F!Y1x)g@av&O;uRjt7IH{I#&anc zs&*QOtuS2bQj>Ni_4KgTyN}{@5bIwd0@r-p=y4~k?GoMYUEYOv`&jiEVbVgD_y7#p zUNIRAOQ@y;fV$5e+oDkrbLMJkDdQ^v=jJYh5)BRl{5XfWgSicB{V5f<_rlB?%^b5eFJ719) zY?!Ig^5I%@mzwucYHYFJ{lGn6OlGA|b!jyhuqKctp*@!PYuNARvG)b)$dG$S$v|7! zxpZZT+5t+GTWJfwz`|Tz>CFg*+aK{AB0}!gQPM$Mp*r@;jrl#!Ndj2|J$UWWb43E# z<}Qi)wmHsWB((2H1xAWj5bs)Fm&)v^%gyKDL~2a$ILxEv)J!ECA-Q@(6Spu=;kwf= zk^Y(RmWdA8Bd6*-!gwxtpjJ_+bRo#V^eV_!IzUaTrZHHNf(#INZP)#9C@jFzvh@zU zIWCc5yjE+Cg?P!xoPqS=H0^V+i}bftR`^J*zG$tEwi&w!RZ`3d&ZKZ`=zpj=a=`kY z-oYn=0*Nt6M2Gkel32hz8Iy<4P`7VcqMv}RSESIhRSaU z@jW5M!*Qo5hVs0nP0KHwGyDr%s;k%Gs##>U5R_&MjZ{arfzZ_ba;cQG*H%XDF|P%h z+}D{yXZIHvjl>a~q?MaB7}1dd@J>_?PJ5lgq9-4n0&9{(K@Aq~i*0Ai(wxV5Z z1@*!7-05XUY3>!k`IYl$pn=1=QuiM1bQS*bsu$%%PvfrPh~2&a?3XFBfaE7~PP)8! zz2`%AMcqWy zxYgJaT{|D!{w6P0sXQ*LDLw;%6KJ6DjK!hEe$%yd!k|Q7O|r$372gVP^`*SFm*1&1N>FpDndL0o8 z!}=hyZUuF?Qs&7PEyXu_vLBz8=Cfo?M7ldEBZxj=pYSS=yIXaVxb?4{T`%-kvTV$vhyfXaV9|0n&woXBQzu%| z1hh;6JANQuHBf9>-Q*N{Kj|BFudGh24{tlIzWpl+g4M`8ETdv~AXqLoki**h<28n0 zmyZ5hX0LKK0G~8V+Lk1^H>hy3ECVHw^h|%@JmFT4-ugUR z2efnG2c^G*D<@(#42_lHqwTe1$lI`P?#5R}bl-3}(tDB}XL}25L`}6KaX0kuzt?)D zz1hqMO_#SKl4evMK*)7cMFmo$8Y+U~@5B=sj@uJ<-Zr*FKHKPOKfbh|Fu2qIaMHEg zxa`5iD;%gS?WlZ?co)nGbfyeilv2PD;{iH@6n?V0PThS7StMejDy$LQg8+>V#7!l$ zY)c6^zaE0QIj)_T>b5K(+O4FZx$b58el0tvdL34360t=nrv&bGS3Hgnt_iE`n7VE^ zC!GTcve?VvAzmlaq~^%u9vYjv zaHERFz^^v&=`{}ql#3{UeiHu42Z>B zRs~2>T~OXGIi0ym5%ooklD$J;#?=ToWhB;bOYXTV1`Fij;)Y1Ry2`Z$~uQOU{C?v z&M1-e6!ED!`-Vgj#xv((B$YW|4tdg?B8i#Ngb8+-hfK~V)16xb7vLEm6;B1gW5dTe zz}+7PLB(@@GH2KpNLg{IHs!oe0Er=RUXHoctO_3nCV0_28STV4oDZ#rI(dzMGT3sz zLRl03wAqU(L1^dNvqB2)t~gAkA43|zetVzgd-3ZMGGmz>F(LcIJcU}~m6~FKG9W79 zupED7g%|{?_Wbr3mglt`o=t>5xnM7NGn4L{r#6P&KY`=u!{|$MyJ(`Xi?tmX-FO}vawGeb3VwD_h#&ykOdzVs<$Y0S+8^u>mj^R z<&Y#qCbv>aR}}GETna-49)G%3n%?G#I6%RL$UOSf`M2dSF+w>LETh?cEf9T)58e^Y z4L&2oa~9q9-G=hMU~XqhhnaLl6h6;#Q(~wNNRJRf7SmQsF6`^-AgS?oEkUMy&~3`~ z1aA&B<7*&)O98=4P%a5@-AEvVPioCEJ|jkq1IsZs3M*Fq5Ro#drovO7n0^{!%1xDu z-(i}+$!Pn&U%g5GiPfAzSUwwj`8ziCTcI|JR+B|`I9(=OMcONbxgCWhN%h(5D0g%pyAQ8y#PDJF2#Q@36ab*8Q<{b%*U4==K}G- zHKR|l9Z|mi>~k8642E4|0wM)8X+ZNDL}C(uViF*bR+E82d5rq2>){$dgW`7~^KkKr z%4ti}#(dyfvf*vL&Zc6oG+N;(661%l%Hd*O*0SjfnTm-AWC=D1jFQHdYe^Xy+}s|# zxBkdRWWIg5G!2W;7K1$Rn$~ww^Y>FK4jS9v7V`L-MYvsUf$@t8iZKuB@!qymIUjX;-=-X;9lE|G?|G z2G#mwPx9>YpT+l<-^SkJW0*BNN7CZgn)cDt7?$S{;Kjv zyT~O%YC3Vv;52`>_y)(+Lg(PX_E!DFq)@5WUVR!pP6jcjBmzlYruJ+-ZkmIm$=i_ zDV`R4GM>Z}|2`*X8bJKua`(@wzapJF{ZWDRO*}Sx_(_=m})3n zp@yTo#_S#Hj28r?*1bnS!X@^41R<`l!|{5D&%>|4U6Vyi99-+I7vo6901sfGY8FRU zha*xLslM-DbK2nRX*tl+l2& z6@>*G`U5e&V6q=x#1h+JIDcme2Rzn5H9P0dRnKjgkX^(sO@EDsb{#KCsfR}aBBMP#cL8Gt&vnpqVU!zs zzxXR_cK@%~{Tyu_lkY9!E>F)03n%Of7a--ZXlf^B(p_-^zl#RCNF+1g(>@&|%DEdX zU3`G;brvyy3A`zQ+y)}E1*3e&QN}%4P^emfA;9BZvvJ02=OK=+S96d>wGTUrU+_`hPLz*SKt9(fcCB-3+2@T-7#-!7H(H{h#lt;5 zXzh6>9~|kLsy5qCRnABqGjh8dUjXnQSrP1zK3Fk=!jlXaW{h2!vJ5NpfUYBR02%{c zQ_xoi4dGh7q~}PzUGdfDu1INs)x=#=QWTZnjNAt2ixRylV4AC*7!bweyvT-rLSicS zI3RWM$Oc%zQ@IV3u7Z<^oAF2naOWBM(NM~b6g*`ly7R?HIaoS7u5cAfY3Aela}V37 zvKGjEvhSkWYy1fH1N&1S7r8d^&VT19A6sg~7w~GTM!_N7#fL>i=%yH5e3Y5I`xG7) z$4NA(eyCFS!62GpD%n!Hs>|QmJjj|i+5oZ<;eD^pm2QllaS1&|B^5w{DkU@xO@hTI zAH4y}9@gH6PNJWii=Nscn~231`}s$Mn$~ocKOa1z)0a+4&Z+IOK1g{tBH3ImN3)jI z)l2q7U!*YIgH`DjWow>uqf4fHN$Q+cj2Yeb#vl*FGofW>h&6lR>9ytZ*-cJVdSVm{ zn7ES^<=dx>3k^&tNJ^Y3Y~t_IiW?b^agps;lh|PLd2SSa93CeGTAR`B)$v|HfiCUzo`=IzPe2#?=iN(RLnM~T z5=Nj@%9^sPDW_Ds#gpVN^zGKJ2X^LQEjaVbE{W7e+E#-F1-ntZ{@_;0o<$US*SWZlX@P?TANwq`eZVMRa5i{DI*yBLP&?UHm5?Q z>oda9q~gYnJSQHz>YMH23bsK+?ctA0Br+D~ExqyXrwlWCej=c;(0X5>Z*-_dEY$6? zQyVB*y5j-9p9>mCPY`G?bkUj_T2X5Pa^=r^Xl*f`g-QF+#q7^>9_U&ZF=VELf~-vG zlOQd+i$Lmo%L;1PtwP}WHv__UtC8Z<5!=0iT%MZ;y-YhYIwRo%auv1L5mtrr*6gq9 zh_~z7yP`%wx_ZY6LrZONbs2wSqk{?1d>&(|IpKhuL73@V(}QsQeIWpKI5o?WTao3=Tz$=JfNa_0BP?O^0#xPOwA! zyTZ0z$V~HW;!vki zrg?+DRx2iEWt$kxGaN7b1y@nE*S=)0Ruk6C*X$m=?(e>UO+~$w$)0j454?RV0BgtV zJTR!~#h&{Pq3oAb-s*CkvC08dA&-5z&z!E0pFA8 zA!}0Ruv1)yRBGU9=!#C)rP2|f-H*bHjK&AX-}PRr3PzTD6(jrRWnWHgcwFD#Ir(op zP~fDiXByr;n8VSKIh6n9T>?wr_mkiJ=OOVQ*KYdc{kMMFzjFOD)eO~-rOf~;gaeIW zaadAd8qXVvGlZNUxD-giaWD`_)XvLe0t!{-@Nr=$CM zvs<|yKu9^vqp2R+Yx6Jb{QknR)Y$VvQKbh7_IN)ZsBMB`A60iY%uzR$uu^y3qY)`g zYrEdv;KeLE0?`?qC@lb|()`+}0?smZ%nLfKX>Xf7lFWK6wwMD}ojZvVGT z#XlqP|7ltBJHCOlydL4+I((gdS3Zvbz_}^6ftM7Kgh*p_$D&AGvXH3}@A|@xuR5}omLF5Rz)!bWmh$cn z{-1l8S+YLRXipy~AUvW9Q!w54`U@Z8`R;!N6ma&Sz9*Wj7cBmLPQmQY+1xA1-@TN7 zyqoX-w$BveF-=!)*Jwgae^*Cb)jVun$%Q&2@vhHoU8sYaDU^PXZLi5cFx$lQF^1-m zx7g{=o7E3Z_8#48SsIBe^$Ol{X>VWZhl9otKa+}#xLR}C@BoaK7WCZL+9i;q;sw3# zeqD@un*r=f`0Q`1_Q_gZnB=Qr{GE7eTE6+4k_%O9+|N-53&%8fz(EIJNN)lagTBWx zBRLc!2Pr1f3RSj1+Kx-SNGw=hCU z46?c68P@{;z1Q-W-&O`i1Ds*d)~JQlHj()d_;mtE{*fII^Fn+7TH~HnC@+kEi^qh< zgZqRl%>;M9_lZHr^i5Xm(U{5|UxKV|w<&>E9R%{~yup|6MWj|Fw5SghZ6*c|16bf)Py- z;b#TD8Tepbo)K&u<739qoU5-S`9D7K{-ddo*Z9`TUf(JPXNXcU6pX!gp86mS@ZiV4 zr4abL>(K?hRK4{|O>ZK-z?L5`@@L}f{i0vpKj9}Y*5AE2io5l$BHS+G)A`!QGw7KP z|5a^nKIcEmxqfA9MA;pucrO$*1>y`DJZieu^Y2SA{4Jc&>9!#l(d7jSf>4cdHOUPW zbkYpkgi_&MUMbJMrOx+0-h+MN``F(5@!$5uJ0XrJyE4Cv{^tXJu<#b9eM6vLzBPgi zm+r?tcdzw1t0+rv>L>rOf^+j<<2M2s!iLTQ1uNl=#-$+O_Vi}N zKo_TjZ8|?YFV&*kySaR1*M6&=V@dS7sOqbPOksFt5H&SEZ{X%&o|<&x{`rSrH!iP5 ze)-wU!l;*-T*>X`-+H>mb)Or z8%seF6tnfEIsb75V6=pKubb;@rr zOHrAIxJ(<88@E>-WhSyMhEPv{pm(@hZX`K_`G|C%DR z@A8W;g|5(^Zdngz{#y?;V7`Nr=^Apf8oM#2QL9;A2(WEZTHa!6co$Q;E)`8`igFd! zR150-ANu&e{6d?~kJ5`QDzz}_-`zxr+rMbohW)Nu&t0dus>eAR=rN7%BuYRb@=@WS zYNZkC@zmHJ;$_Aox#pFuEw(dlYXeVtl7naM;%JrJEc|_rnJ)n#m0WnJm=ma`Hi&3} zsxOe1*n8lXD>Opk><(75bzNDog;7=nDtkS-vNey_>qvA6j_5MnG=FG(551Uq9gjS(*6d8oSx@dBS>KveQ2DxlyWez!7GV%m zDUhjtXFLmcSs$Z7dX+QGT=+xNQ-IV~lThzdOnkXcFu*f2~5 z|I*tQDv~FYX`&;CobVJtsf3(}o0;Vq1BkT9`9hfp5)-k#)bO7ze-W3xKc*v;1SUhNg=fgy-yfWR3sNAEvih|B!dY?d|JF-?te4CK zw76R z>{5f~sG{%g$oaK{AG3d0oOBgo=3IMPMDhT2Sz0-??H}Xx-JT+SkR8HK3J^Sez?!D) zaM;@JZ|;?xnd+s$Q+4|lxlvEsr0t^Y`Dqwo4uqH}LAzlc z(!)EQLfp1#0LeH)&4%TqtSTpK$T?*LYd{@m5Zt{(f4x@>AUx3{k@^%ZN<#(>upS9- z#ViM{HAfU=vme##0EC;vY&^0gjuZL;91(NP4DoVAdsB@q&TkyBYU(<*6xnfrP36R8 zjZjGiq{BQCz8eUzQ;U;81%|8Br{;jP>UIOZrNY6xbPLfhr$W?}V^)PCd6kQ%OQV-H z>asYiur*WV*4=*j2JH2XyrqWd@^we{kmm+3=Irsa=0Hi+Tf>*^T{OAEUbGSzSJS=D zJt{7$cK=@hDH{(%>#P5(s=vOn7Oo4v6O@dYx{}0^TV?{|t(KqT$^4K;yd#n8stt7H zS&!)TowMPk1zyDg!Na50{oft9Gs4qHGqFDla@@Q+IE;Y@4Q&w0+vB-{aD$VTZ@l%` zpPjkmt58TAB#2^?(jR_ABty#Zy%ZWuQC6bbFal6 z{dic0G}9L&jT`SEaDZMhZ#O8IXW_%H4S59p8 zY>~-ku+$G~8O!bFjZUOWxYWSPJuP<}34~JSI~rBwDlxDz?B44^_Q;b#B@%N616`Y3 zsh?l(to68hTx6~nZ5esfp>*@ImY1hQGt7F*c7N)+w59@50MFHjPGo}XG|{2+8V>8^ z8KW;$)Gi=}-7$I#6NRt|vG!9E6oEMX)iKVW&qKn$5q`*TY zW>&~2rQJj!;d?s%$;oh9!m`v|!=$|f(ff9z#v<8#LMXfO>iiBG+157~b8F{Z|AhPW z|8^}ft~y?<(SG*!n`{4IFW&AS!5ygae#)5Eo-Le)i{G z-v6B0(|YB*Pw}^vy4B);_@*OuomCHYHzeG#(ynB-PV&Kg+0T4F#{bMKJ;JEtT|7p9 zb#ibuXV)!~Z*XZPOPZeJm>)IM+*lcT)I~pPE8mS0(9E%muGxFjwpPoo&!N?M${P^Kpmr1c zT+f3lGdq7SIHI|RMSOaaXgYf$fyPXlCWctJo@@UWytic-1O8c*Yn*BHyt${v!RlyE z&oEm-Iqe41`kVe#Y0*07P{DkD#2!4V&Gde`nZ>r5+K4#4oh~(ckoB!&*o?109xTg( z+-NVAG!fBoz22Wz0%^PhDDytFeha%;v^jQbX{&7~?~b^Qp=G${-(Q4FD}S3f z7L>9*Bv3*CSO6NWT)mOI;^h-5-*3?^;P3kKYJhREAtmm!R(GJVj|YLkJOlWX6d(#k zu1E-XvI@Pu@PeKy#reKlIJbVb+1nb^(tv7~J1kh~__#r{S=N($Ha_D+?=NHaH=?D? z56TbZ1Z+XPLVPGx;M!1ujN$IoN=C944X<#iStmavKI#b$SznQzf^N+bT1d^+i)l&P zQZdEhapmbKH$LijF`Q5s`d$ogJKLX-jQ~&>5>x6UT@KxwXp3auTv>9&M?YM z0YMO_s}Li?k$q5OG4HQuDBPSQZBdPg!1`w~5>~s2CCcPng==9#o6p|2Iz?tLg0+S1 z>KoJj+;XPYbvE&f*sULt0(3@{cn&9wYCu&c-2B}Sqxnz*X=i9g(;7Fxus`K;>}HbX zw;N9&`M^0@cKKqyTwXeyNEXNn#<0I;A1K@EsQwM46z~^#U(N3tcRvsJYX2&;{5{y? zzkmz*XKlnX2{!>Wm8z_nq{y`ZB3rM5(-zk$Uw0>`S~$oT;y}M&<$fdbs1^8XkZ2u; zkSjgZTpq=Qixk!7h}KdSkWP@Udeu7Fegn{gZX}=w+^hEjFr{~%w?HZl9ComYnZ#dQ z0R$w@9i$%onXlX%r2M}sFu_{@Z{JLnkdtt^JAN*GXxfnjww2`@F<0~qDq|z_OJo|8 zc-$m5jeYc1-vpA+Q4`fj&yc096*=#TXXLGLMBa3}%_~(lfW#s-S1F*l9(Sumu9@jB z1WjAm-2Xg)F;GNh+PL-DXGDd15YzI;fM%Jwa)d2|U7U3(lsz-jt)^xy>8ZxUd|rV& zCnG^a`4^9j5A@%9G}C~H#)+gnpQyeDZ<2^d&$G?(ASY_$?o91DLv{3GgQGBvlJYD% zyK6yZpKt#^?7d}FTWh=b8{8=_1zMaCEVxr#LeSt=2oAxeEzlxGgA@sn5TIy~7K#@y z?ohmFOVLuS1q!9M4r@L8efMMQ+54Qa_a5hr^L~O4NhWiSFz0pO*Y*GXx*9dR;mz=L zsX!QqB!Mh34UiqyHb&U)l!&9qd(-0KBZ^rx-Oe?uV!=U?pbRzDHt}lpBr<;*j_G*B zr&%Yn*EZv9tujnkDaC6yzL2WYv*~(JeGN+$QqgwVe`TaP3Pg@3*ujj+y+eH%QJYpR zi|FR;_P`jl>JkG;n=Um0yhru5!t3ezc_{ItNm=U~UGeUO^+ZR>(wj{c&!TcFOkpo% zN?-b1k}4R!0kzyp08{-2=+OM9PWq(_E5;|{Y8#!u0s5|<=Il-}M1@73%c~@RTj7T5 z#Tn-bN#8H)a*3`UHe==l z;`DOvgYnagZ3R;+kZA*6J+S<0brOBBV022Js(;)0Za?zpHM~LDlz;b{q-b#hEbfhtLbR|*zJI1 zsuxbjg#YxUTHSA${$-Y8wn^>0*YfxjJuAabG{h<2csD%%uW3frQx<0Q5?)SiFY-nI z25OYMpvkSTH)ZL#3tu{>3~CWiL2p^@QIJKEs67r7w8+e*yZ9(x*ob-7Lg`4ro1Vrg z5_RvIhqm{+6QKs=&`eS7PEOR4)H7IwZ^B1;GGNyqfQdB|f648LcVX{m7x_ClO?y0^ zH;sv=lfbQd>OB>hXc^8mDA3Yov1d6EZ9fBvvn?QS=^Yb04g?J6_A6SyoC=C01vbsiB=e@$XYeKq-Iji*Ish^i_}Q2VQY zn&Rd`La9>W(ZiQbnCB;a$<#1B!X>}LYkbW!nJ1E=-{Gwzt`Zob6L{U-jdM_#TCshQ zp()mtgGE*1Q9g{N$fWB8zBk!@3u)lVkxXVYPDCSLK>3B~zEMCMn7u^V>6P1cBxf>a z?$P?QW|mqWGfpT4-BNNpRIE&LU|H~s;AQJFd)k7fU&hedfc{hQFiPUJy}62lz%MK1 zYSn@mb7~(#Akl!M0E($!lI$m_{NmYgRvAmd5@2OVv&X3gOPY4S(m^g4D%jRkpur>K z_;Fd=UC^&glBF$v=v|XubrRfgCbwI)mJYN5D2CiY0l1luzh(bND7m{quP&~8h1~vv zH@_N4yO`Ad2Dr!o;nrq7<`cUkW?>@P_`8Ut#aHFg6Z%$h{iStyY#ezn@71>hiHyWn zsvvBwpaJFKVugecstSV#9tpMVvU;xASzZ$Y76p^I2wCdM6vyKf^O_VzdlD%pnO>xv z=0iCOoG{UGgRy;UVHyi_ekW@lWxZutsK?v{=|`ZyZ8mkvbV`Gal&o(mQ7@y#lt7=zcMxXZ4_z0DS0q5fmM24Cag)}-z_a^@SUTVU) zP@!bTeBd@;qr7K+)=eSNJUlo%_WhANX^9I~d|K*-6o;Gw-GlQQy9U8Fx^qC@HPPxl zmhsv++t1jZ`QDhB*>D7*5C}g6{03;}Pa5b-{%r@B#3D}aQ|-^o`2H!k?*fWqp4$7O?<2Jp=xbbcc*iP(Havf(j_-! zB4vgLvVM8L?l{Q3RihwdSE`&ytRe&Ia2<}D(v#4u^CSQ&Mwu=jC2UQyF-=zKDSD2X z)5p#Ug+!@o;3vVkAe@{;(gVc-t%QI#?&{y1t*<)*=HYHS`Rm?kVQQRSPU zBJ@4L=;1fh`LYYupQAP)seSf>2PUb-TB?@>{A{}vwi}&q3yTHE!pwn=dGNB?M_DOZ zTlr#fbpr7l_V}`?dFAHp%_$AlnUZMzciAN|p&zl{d1Ji%uVaID**{+jLmngq6?2k;VlzIoZFvHqG_*(LmBsTSrN#)D{j3i*UcPv>J*@FuG zCu8sipQW+oOZXbD=>sYa> zCcwudsJ{FLu>768Qh_{@`t}Y48!$%7GEPP!FAM+>QEY4shtA z{|=v)w1cb{&pzD$b;mUuJ_SCR|E6R`OmtXy?ItyU7 zyokfEXNIf`*bna{*eNzgN*Acyf2Q+YPqJNxuR-&E4qg7e0Wsfg z*qu*auXK}qhnuA7fifd!jpW0D+(kKNi@(s@-(MgI8rQn}S7}FPt2tn4iwZYPb8eiz zIhqmF9A)rzNHGeii}#BGF1HNW(je+J+JpyraRY&IdCG9a@EEbx_o7(>-&a;VZV${& zsqez7ctCcCiEXn&aV@QQlmVPk$M+tz?;ff$v_(m3kM`g*lMlH@u03g6?2X)+yMZ;7 z@pLsM$Za~+9ZP!#up7ng*hM)?pfw4X5D_b~4)cgTi0QKq!$MCZx_cl*NlBIKIQ51< z{Ov%5eNRG27(Y7ml|!MaTj!oHNJ!4?gDW-3y43(%l4i+GMfokKD!Y%Rh2yO4LV<cYv|})5yjf&p6UA1eYyc9&GJ-BYl^%=-oV`2gsBCjQD9p+TUDr z0Gh8;C%Ad^^OUBuz~$NJjpPrYTR}tviiL6E*F2I}zevB=ha128^+XBMqANFndSRot z+~Fy;3Src4)r?Z-2gpH;MRyku_g^zyj880Lp1L%Mh=w(-O`*nGCF1!d67Q1Ihadn< zfJu^45D5OV2DtB1E~^2|B04=bqd8yb2SPQ0qyYE1qZHcm+p34j+6a%&(HE=o?V)PV z`u0FcVNRbmsYYV&WOwnKV^M}Nc88e62VQnZ`F5T8kzdOc`egF zZy&p>MoNq~i&l&xGYib57rF$lyq{XeQyVY*s$e1E9c>IVodt?{c zzN^smpk;*&=yI{*_~C7iGt*Fi1h>qbw+C%%x{QRF6l`gMU&JkcK&Tn7ZH)yWs`%V0 zDDiz)tj`tK?GOV35y_Z2i5BE7hqaIBjd@15;uQ7G)|K~kHkm$?%;qn^y8C5wzCdzu zy7DBtG5~^4kbuvV{(L^US$oWnEArOALhPqaJ26fKtgjpoVIm6(?)%q;c= zYNnRi?BleQZ{04OQNjIWQE$`b{ORS@zvq9lS)21bpL#fvsW){G#LrpnDkJQMpRNqP zmWjjprN^_Bg1{l5U5QB)U2>4@U~+MP_=#up%c9dz^Pw@*Z)Uy@&ZTm{AY^H%n4RIr z^++H$w`E`pYAdESmvgCyaKergwuwhe5w5Wu&j^?R-E_kt&?Wg(#s{2R+;?Ws2u}C~ zA-A^#;^RH#%G*{Pll;Dc$GJccQQ;mU>N0uL<(~cDpkY}ecv)g8TUMp*@Cy%P$%XhcmD4C~joNTm3!mVqViCy;fl{kbu zWvU{>plp)77qw`2#`%c`Kgv-&3XCRR-8uO3eh~6}v+9`_th71$$NOD-Gn1}U&n0rx zoS%+KlPc#2Ws_&-HXxT+zz)|KAG>UK#AiO7>zKTCGSl|;a*&1|T~0yF1pvGXZ1ArLp~N{6q;-+k8@ifxQ78$y^2o5Q3^|&iB**DKI|iSy;dbr zsLExtUU33u>L|dZ6X~CYYGl+MohP13R@n*f!nIJM+h(G)gr88tx7LSl!o)zJk6zlz z83Xm3XSa7uA2YOScmvgQ0k&cNp9%G=l5||tkJiy-zTU^ zqeZOqPWxh1W4Z8q)Z?T67qD_MvgXJ82mhK+8Oi)FH!rz|L14_{L1FKzW`U6iC_}8y5 zo=Mh&5rO%g@QBIWCXfCy9sk89xykaX9;sef3EJK{iyx^ppIPyxiqe9mWu|MW#y)&) z&M5VRKhX7~hD#3N1oS=xp5_doPG?#6QfnZ{W%ve@@2xN$7C;owMdU^2lkx)B^wA=> zL(DF6a}4;Jxy!tsF;J&xkLqWt5ID|~lL!9al9{Z1T zMBOM|$#d~zJwyz-u-cB|zIa92DqCr@cc%5o^@YMRP?^!?YwP^pcqg)Gl%{xo5y8Ia zl7>p*2+&d7sXM;B8? zc+X4N*^QIF@i%}RmKUR%l#`-+y_veo_3`|Vn4w$#3`lEi`;(LOIehDjY|UJY@jgr3 z#S!_-P(mUi6P4ec2+V&)`jeMgrjD|8?k_sFK(&qP zV+?3*FblJ2H6-IrZ7IXf{b(xjdrt)jf;TCFpGz%dPHS#9M3p4a%)TB` znvhngG@$voNHdDe7ba%AazJQ$or+}TP;9U(c>B)deW7$7e(t_=+7KN}tKag$K-{{w z@vJEsJyGcB%G{8@0H&~yg-N2N!TKaY`4=8lruRKVzTs>`Iyly4#MxC>P#|`xpXzbF z({1(A$`;-N(>PZ-Tc11GM)a1P*winXCL+^huLN`k-E4Ud%at-GJ`#IybT-FUNoJ!u zsnC0Pu;8G?kgqk3E>j7ST!wI@MA^Kjq~JwICTn-T-f?2!#)J$94>m$ZrvQ;5k*!qu zQ9EMFDzgvkU56l~i#DY{jt!=M_$h&nMXBlo-5j6GgD@CF)?Gj0D5e1}q+*Pnu!+pa z!GpB>O97L2q;UFnrb!&a)Ti+-ht>3C{WQ!h9uso#f(>f=Y2_l5H5T zc98SIW!ejxj#K9~;3gU@3tr-eX-v7z>+7W?&FN$^Qw8pES7;i2HD)0IM?Wsci+Ne) zJ}-rXPxcw^9PaGc+0@oU*(%8M#aEW1$W2f7I`u+z^KU&>uBScledq_UO7z@g8kh)e}ekq0iSw zG#R%$1;aUt8yt}aWxu(%r?c?XOq#t{(50X)08~{g^A-T0+?0Jw%9=Hqdg0{CMKyy1 zjT}bPUk}@GyyfI;d^_FufG;ei&ukxTPLx!%bNj4xp3t$8_0}L(%FwmXnW6UPXkxV+ z4I5Po`9QBp=>bxQ6P`pCA8EF9BEnFT1QV%!?;v7C^jy3USeJ(v#dj8?isQ!C;{y_dGbTCc*o)n?l>9R)JU0yrhwZ!)nBvu5Ab7V@B z9F3yE(W|0`T%uAFOkg|7c&E2X!8vB}3prA%so07{gDhyVBSl)k1ly0J|7bgQYX2(e zoUhUJc~%Qjm{}i$sRa~0(*5x3{o`Dh$++D#zH%<)`yWZYx5|p|O*VhyreCKt5klBq z#mRFQOpuN;BhYR+#Q}_I+B;%U3R0)$W1d%Z@^6Q+KtzR&vd{nw4cXJ}v=>O#yazWi zr@N+)$l{S!eOUZbqh|!eS<*R&k@BJek&>SE zz(|IDXHhR;GK*114h7{piU4QQ|150LExvI4kl%#qU^>FKy;5s7G%X80_XYSWr_yR6 zG-oT&y0oTd51xN?5Jn%TOxS59&Glv}q#qu>S7 zIw4N2#2h!nnU*EcgG5*8*%nfCMI3v^tXa}9gK z|9<4C&902uH~hKN+EW&f88%)+*QSdRGs0f1_~Ix zO)Vt7drLNC07k&D0hODxgcjC(3mTOP)&HZ z#s6(;Ja48~jt^7YF=^#RuPtP2& z+JMSz4~B`7>f0&{5fis=Kxw(TwaD49d+gR{Cj;>hjk#Uiol{91va`n6R}z0`patN zzx2p|y~g>!b$)DK)<&azQ$C0iDqT#?QPiJ$40A6Y-zYDiDp!$fTPvm;kd zl;pj*k<$c~jb!LuF$v$V7McpYCQ$6|k5Zc%GYfBUuYp{8$tbhDsqZ2YK(kdW zIozOzvFom=?=q@uK}uWr)^m7)a?3U8O~MfoN_tOgzJmhR$XZf~c_DK{)>nkqSl_29 z56)`3T2e=}<*YE4DP+@Kk}*2Yi*B^`S9MGMv~Qr{CK&aG zOvlcB7$@Ce6u?nE_wSET%loFzHZ6RioU_R1LhL7&pXr-PiV;e~v!)Mobn5n}c)PxY zYN_5$-7{x3p=#aXjg|o7e$hn{`yAnwF8pQQ(h|y?GePV4usPb9+mWj_@PkZRVEHBR z$7gP>*tOjz~R++$^ z|4mGTzl$>d6;45-^3hdWar5b;tfo)S1A)0ELwB<2RuWFInD5Sl`-(=lCp*x zmaJ^8r8<3X_^e&`b@_g&RRp5bE zmIoIu4`+@(C;s5`@Z^9H@blCE+~NQIgc2Cd&EA(JNazr-Fb;(ndIyd3M93leIz^Lm zi9TZ)ds<$WTs0D>IkaA9`M5Rdu_f10K9Pc=MoXe=?Xz(!)P8y&@5{R0w^y$#7~UP+ zR;hR)FmH3{x)1iu?Wq!XmLUMRzxMg{H+RH8fc)P+gR)C3;MY0AmT9ei6zli+_>Zkd zgfn0AUp(Zy;pngt0axj`zeC_;7S~EulxELPUCTps^rtt<<;dL!o%<+dK`#2lwa6?c zX+w?P@tYM~8#}46^iP39RU`N1oz1qD*z2nUZ&6z<$lo9l{@1?x|L?qzXWvIrz~xgH zd8}#?{JX|Ke*52`?zJ5J0E#t#{nV$vrQAq#biZJ>vj;u?lzo6J4wgGRp#^cmyD{0M zC+Oe^brVZ;PA|zA-;YdEh}>hGx>wvoH7OvlC!QyRLOX* z`u^YZ*Zt)hPyxTi;38!K1Tj0z5aEnhS;%NaB=*mY#UCSAC{=QD6~%tMmi;`|IpvlG z4INHcw*3td2~&VDP-7mGJ+7q@l+sM(=Rx+q`LZ?%@$^>@);vx01$-Tld|&tFT!Zsz zhr!gF;mp1ay#&S=rE9S+4ig!yJaAX`<$40h+|Q9$zX6Q*_*FLPFWvrO;xFXR5%KSW zcvmow0KW^1XeDzXTj8s%T%{?Ap;4#d#Fn{7VleBz+|l%spm1Y%D#A@P8?k>&6Cz$J3}_mo8vv<@0(|iMa3-y@2LV8x&{FPY)vH9RB8!F!a~1^M6Ys|Czr2=^x9! zujlaaZ@0I;$UpV2+U@&U=O@*Z}3qh#U<5yL)HO509d)GD9Jvs-YTg5eyQod z=}G?YkJ7)Z4UFgc8;M`{GUB;3q>;5) z*9g@aF?>dEP6Y9VvXoU*Dh)(M!^!I3(V$4Ad+NDNR59~nxVD{?a$TS7cX3ex{5Qc% zs=hoosv03)VHP+wjt0+&b)1@Wakwj)lQ`7&8j>z-2>O=U#lzpM(emBP;_NCsIJ!?& zoil`ZP&C~3RMV-0(1R+&E0Y!fS&J)T&K%rz$?XiZU-U}@m96M~goLAq37_8d$n<1L zShssAIKeDRwQ%kh$A7eMknwhw5WHDf3Z!+7lB$ZZ`b4thgtYJ$_urW>@%NSvUMdRi zX;ZpCnNLF1{^r&I;YI^_A(pZ@Yvs%hYaQ`+oM<>uv7do5o3(6EP-0frt9tqwn$~QC z$C)LMFkIYWf^TYF|6Qq&y=IP<8rLkC8I0=9CzjzxTco*DXJf$#bjN;a_6Xj<$HX+Q zSI#tv1GTwWSjYk^I5HWtn?K&t?w4|F;Bn$T`^UE75l%+}A{E|{so)uj%CDJjoUP&n z!JI`&$@v<}F`pY_2ldW-C&3FA5E-6kYC=b7QbTms9mtf)02Af=Lir|!mXR$TSMXUl zhNsE@?Xv#naLo6w&dx*UYYh*<>aLPr&TVeXd|B6BC;N7Fr+wU7qQ~T6Nul0ETFnDf z=*%kBwvYABT@-e+7_g-0^BwzQkp+F-urI<@Ta*#y<}j~SybCGC#~qyQI3osiS-!8|f`qol(ehzAx!$yf}VRnqf)A71N(JhRlo+5RIP22*VI(!<% z^*o;&7X-`qZG-rz6AdW$J+tL)W?;j57;W7t^tQ|g22lhC=?q9DzVN`pPQy&QYu?te z-$>=pjTvn+eKUH^@4xpjs*|n@6jTvd({3GDNed9lnIc@$lBSo-B}HAEVIqV~4UN(A zaIH*L$WpoZadA&Hx(}}`?DHk=m$m7{UP3P6V7u_mn4wVoS|i?!0JsDu*2mk5(2rr+ zB6Hz|m*6x1;1%uVH2G*U?=*9vWhDjTtum75;^G+@acTzhHM$fc!dU4MIl=@m5HEm$ zzJY+`Da2DbLm-82?5NjW6x8_|pG8&cTA6xN+=@_#IsniqpqM*)V3UUK(P+i$@05h5 z)LS8n2Q=h;S)u^`AK0%-%$4rHpC6QuN^e*^G-1q#LLJ*6NGII;wfOUHXCW8&+ZdqJ-&=T24uoxq-d|>X9l!=+GBr%Y_G$W zeUabIJZ!Y2H1{xV%aOyU-tU8Z;}L)p_pa1=gY*WfBZgd?X~yNk){+>n2Enw}G@Psa zJWDscr~i^kSZRj1?7JJDwq}THkOd@C7hcQjzoQ=A&)~k)|MB^!d0FLk;1NcB!j$~v zA9*P9gKVNKnQ~U@pQ!Rsy4fe*@BRVtHh+zN{JozM@;o+b)#EAEvHha|!C4xkNIgT0 z<5zC@rjcbQCntPIqILqh+Z_cs)NXsAW(f7pMKNp-{r~RQf%v@2YMm$b`E6zwJ(U=w zZ!YJ&71BjW$gui6u;J(+q^Tp#(vUF0_a{q*vC)JTu@*skMFw+KjzFjmx|$F7)7 z>ER*Zd3CT{W1yg4Czv$7`-C*Y1Pa9+=&O8T8-?We3qwo7GvAw4@Fg%EFzqg%EF;NN zmzK^KxSzcJ4IsU0IFF*$A#DP0fJEqx2>_&?6drFUowCN=zO;XtnCX&hW41do*6_yO z63$_WB2bNP+*{Y4dipu&1+JJ*`N@Z9PzSdWMW%=1?D?It;74@~V!p2(7LncQWh2#T zWI%tA&`+U3&0OQ%1N8DQ&Ls8?nGhRm?K6fpmk049`%Rkk^>g%OzH$iomouHUM!uZM z*RYXsW8ToI1s!609%_j+yqPkU8yax0ctoINro7{+1+}3J7dzEJIrzk31CJ5IPo1UZ zo-#FBeQ&+h>U+ANMx?>dXTxh{V`cbK#6e7C@?*P%X=V_%7aq<|II4kCMbj59rT)~( zcz!7li`tysTc}fv3yB~hQzjqc+8)m)tTb;OH&vIz2U?% zerHaK{T1Gj(rwT8KtS|O#<bl3N#DFlqbGy}8CJU+DUos{>8yT<&r(50O?zNh z!o@I9bE;*Zm8bWOg61KHvOHEruK3s9equp?68q;z-ig4WGXTpwP1)80n6M` z$IlgXmIj?+2$6=ztndRBSs6Y_v^9T3p%jT^^#!y?ngUNI}l^E*a4_oLMuIaR8u$^Me9ZG24 zxVP(vdudezEioIT%!;lOPeU`*jA>?xWe`^-_Tb7E>kvze=R2U~#IYG)Md+4y{wRQ` zKJ`$3vxtUE71}g!fGuG|Oa8#429T=aRqS%hH>L489~+uCLu!DT4dRHm&dqanG=Xjd zlX3bvdlPn_>+8J>^4=P{U(-*v%hN}(CGNzW_NoKvfN1~yZjbN9s2;ltX&Yi8_ZH~q zOILs!CC|AlkMq+*?Yk0p)&CGQR(NF%RV#>TV$ATw!}E9ak4>&NHIvuH&W68OTYl(# z|2JBq?o!Q8oZDI1&4%0>nczVZ0d6ChmMK}UIfMc`G(98hn_9@8MD;As1>(&CdQ&J7mv!+eoZQMD*|TR}zU`&_H$Dd`&0#{{7<_)b zlpa8RQ0MLEmttm?r4ZKqbiQFhH!o#p0$INRL{Xtck9)3n$7og9H<>yO`Gr${LCcyo z1SCBr^}Sz+g5A$&KT!6_pL8la{aJZZz6;Y@Yt1%z64!_u1SLfW-v68y{{H3mS~v}T z%m^q9ArWunJ(=g@dKNCs%rSC8iO}Qok-^AjwK@JczDXN|FN7xbCL1m4<3Lw=YG;Cm z!cFzBExD|}Ka)j?fowp1HgWtNJn>I^G?brB%vf-Ngyr~wleWlw5f&^U9@Xc_xhBkQ|22CI<*8Iz&0NlSbKLbh-klAj0@-W; z3`Y_pH0W7rShRsy9?N)NY=x@$8r^~kVQTAuS>eOL1}_Vx@@C+;v$k+wQSbR8n7yhGMHMIKqeB4 zO!>d<_H7*+reb}Q9pVf%dPmtjCx1}WR1LBXtcENR5~%oZO>_x~rZ0S{QH{pa@!5Xf z@LjibdI##vQ2xs161n0#xu6ds3)kVryyTK;nzDl9oM`Z|#TGqsI$HgPPN~UPxXtR| zvEYG{(YZR%6eW=+t|OUhqN*O?3s_1452d4FAzd7Dp_q9%eGV&rcYl5lIyym)IGn1a zwfrrN5os#(-GpgJQ3^uW+Y_LWc1@6HxT-t1ejLUD-9d$p294SCuu#dn3l2>{OzP8! z>G5LY>ef^{`Y8n@a`n1$6m*{zRRsezhEuJ?llk3;wG~*3i{8%JzXBV4 zi(RbWwUlY8&lG(#zFog%T=t@BLbZ(kr4<7-+Rz&lSC`d;l@l&eO-akq)$mbrSMohSN-ky6EV>r*#KYvnwgU(IwCouviq%;}2|nE@wr$+KEBPQ* z*1|kl47Dn!N^)DBCHTYZqk-PTG=s~2Spy|qiB%#E1okvAe&Q~|spR#|BW8Cf&Yayb zBB>_7^|3*d1ABY_6MoDS@BKQ>%!XZe@rwjUeLXE$ zz|l*qpU3AJWh!Ve!-AtCzSWY*yXB%B?%NPy%bcjfOy_DEkh~NJdmJBh| zr9~^Nf=f1#l`#Wi+dK5)1_^SzT}7^DW!YtzbS!I6E1)4H5mCSyOEv!!Xdc#b?JrT5Iw>fh9`H&20B&AOq%^miQRP*lv_D1i3bRknAs` ze+e%LlFFeCaTO&$z8j~3qspej2bchEdjy41j8^OEvrg0)CNYjCioKz(yUWYW?wr$A$N_-Q8@#Rt} zJ*m4T%nX*$*dEjE1b@6(O<@3Y0{OTgag-~qN$buVbAN7k3idK0N=Lq)>kphGojw-a zlEcy8MU<`Uq)`H^-f+i6xL!p0;CRpHSFpYp=3^`L78ew!_mu@p(e>lw>voa7he5&7lLws~{atElU*>IQM?AiSas0*I!_e%5`=zbqTB)l?NE3s9C|-0L2+1@wWmFXwX&)EBr5B(rbv74Nctx@? z0z=-7{_N6$c51>^WyZ@ETx;Gz`29F_=nG#@sq&n0yUYfLPN66L7P z9!<1HUSN1~SuV60N^Ivco2p)n8}c3h8Q~eP6^`&y;EdD<tP+6h!oG-gdR`A-|=*bT3{UgoyzzyNyEP%(-*I(gsOj7m__^f)klM?rZe)}V0f z6@h9~_I8!HZ>fD%j`2g_<$xU=@o41U`vQ82^u|c2te%uHqWN`(AVqAeAx|PD-rhoQZjn)W60KPLHfeMo@2G)UXyfCyJ+8%yKo*6G-9)*9ZT z>DammPa5TkhYONl%0~?{JU%fpRZwI^ZvP~Ed>ZyM5p8x>leN>}NiYg5AY-qEE-=N7 zRkR{71B4grwla}1pD(%E@_?BL(o-7&@!`O`x_q(W%uNWX-d2>mm-!*e7jMQ<eI7gp&N%x*6J3%Qpq4xtq z>}P@aRin;2c`g2q%zRU8P2n=$llFoF$9;Z=_8~{?AT$Difkwrhbjs2k55ME>ewltf zaeT&**{Fv#*6X!dD+hAF7jKBKiw`0RWHg0YcNFEKXFrIDnpu@>jF%@8jzpW|0oXRd zt12EjP>@KDz4^j3c}NRfqRBRGPQE4x!wF~+?@CazsLqzi)>x3F)bLG~cXr#&PHwV> zffne^3PB-Ymk|VBgl&Jm$nA*CZ*SEa42LI7A(Q+*Y63*wfvBS7*rBnTeXJ84BW^z> zfO+1$<`7t1EI|Eg%guCV;i^)LUfn_n&F9g%$|=&A!MBoff6jwhs%a zy7Re(C$zBkI3G)bVg<+339K|CZt`;74w`v+Rd%jK>wKJ|IET}Y(zB`-U<1&57hWE! z&mAR%Lel5MZ}B2u--O_fqBV7Mg4juq#0h?xM+Fi8`T@&!V#%|*VH;Btm3pdCq)HMY z%9>E~@y^~)jXxbL{kMIX(7RWKe*Z96dMng>l2?O-N>Um{;oKeBk8hc6 zm{3|!&d8Sw)`vp)7Qju1nf=19^d37rRD;6ma;iNhlgo#M;x9mN=w(;A43Lc_Q+O*y zWu0Fq$hING03cm&TWV?*`DSBPwRu3IeD)anwy*hpa@GWVY)pctciR18SCl=Y4Z?>D z+Zd*EdR4e18xKVzi|NOzoQaxtzYeJ!h#l>{;^M|s%jl!TBgL}yOpO_>hA1<%B<%3} zm}zN%wl5gdCMqhja1%fCkmG!UNv|^MfXZk)eYf7Sg!W;*cJNzm z5$z`KAmMvLRsb__zK+~#xDckLoV^!pqN^5g%VGZ#1_3==&lDV zy1h_>N2VrA#hKkG#m}+Z?`P?;9q#nIw}<|_#xa{^DCL;#50guk?`^{~>M}mkj>$F)nI@NBuRs3{Fq6OXKu%|S@f-0TBsx0a9UB9W_Y4q;1Y`x1Y&)FYNGf=rI*?S_#Wvgh3)+E%@pOmAB zcY@OGGg&dO!j|AHm`@d5mI<#J= zN93%HbGf}V{$A|&aDe`9n8IT;$dd-$n8$?z}imRnwNotBRzT7ZPE62tRV~C)lgAS;? zydm_AqqV-lO)xEjCsl)u`qqY;Tf@T6ktjtd&NOSg$1-5CGtM-W-F zlfGQRCY_H2l#cOpNW=Yl2Rd)50*GrZN>3{>?^qX;hQZ&H1Ed9_Boj|m%`^)~pBTL# zei=O@)6KSWW&6JQy{lk5Qp=cDX^cX^vzGAU6X^;~&eX@eKqGN8fT{2PM^7N`VjIVn zg2)xa$mVjVN}_@? z&;7$=s!vaXxqf=Z*6@Bz5JAq|yPq0DM}-&v_1kI8vNtA|%}KEL(zI*q_TxJSrEDW^ENb)Q>t6(SH>JDZQic!kE2r zAYFIViT#0^48vv3bkD!2x@9~}TgvTgL`~tNoq+Z?_e zYEzPnD}k=L8nSZd3p@4^#0HLb;YYm7EO0yFupbz%Qmdh7tO= zOQffG7H3KX%t2Bes#qwb>Q)lUcvPN9K}k2M;lbr4c>N=TcMu1kL=~>Fd_gt-kUIz& z$y}^ljjkJcjnmS7VmX$7?V5Jt-_{|uQs}uALl4O*)Z3nva2ea-Tkx&DF-l(sPkLMj zK2FKjwI1KEAOj+gGTQn6`IpE{Vt~Mo?wVDBR~uDII^*U{ob;@Nh{-(wkV`f0Da72x|Kjn?s#pol_OCNDRxJi z_#}b^vla9d?4>CE?hE#+?6UZdW(D7r)Q!s1<2M$h2fE>-2vozK{Ab2J{-BU6U6w{< z{2>?r4ZuA2uINl>vH5?ScD}_PXJ*RfN@L_C__@|u2BF|;7}Y?L(}l8!Af9scb3ETP zr$MsA4Alui6i7!{x6gM7PJX20Xiv_ty^iWF)qau|)IdFYV>|0+>NvG4=aiksk+y-j zohs$SnF*&^8LF=#YSRl^H!iVB#x7s3n8{+V1xuQ$MFzbCt+A@w%fA3iAFE2ewCSs> zwI}t$AI}Sz?Vxe~>+EC9v}55(-82X8B`x|PN~L$rPS1pq4JU?LNRc$CjOJHpkYIiv zKiGY;l=>ldoAW}i<)d|0LW%)Og)q@yB-(z+Y3;;8MmB5A&csh}R2^7(726v!g1yv3 z0b1+$1Nq!KAC{c_dKHoqZe;cp4p zkEV8FXENL|#@}+9{5hj(x>GIxNKhyL)Xo&& zNOLB1;>(PMc+?mT1kdHrq;>b*%VN!ibF(4n(DMw@s%hSyij`xSSrIIK(_q?->ci5R z%gy#6h=ch{(r3i1#(KQ-x)2lSFhykm?K)XqT$C`!!}Mx$3vcxfviWtLs4+*O?UCGi z72~)zvnfu#`lujx3hgnv{gh3^-vBP;WkdEW8zcrL0vCe0U@TtHUh~-?Xg9HPzwt;9 zZhDznReYnFQCwA7UYefLF=BCwsmU-@z4qN4Q6(elCUl{!sQM^)h8{jpJipHJ=1>!t znAe&smsj*ScB(Xp#gtZl%CRm<^X-zCGpqPORVo?^P@rU+skgTn z9cU8_PPIfTa^t|jA`k{*hsM(+(f*oHZ1Cn>Y06r-hA-BnmG(2G$laGJsO;W$3U?Zs zB))qMh#~Yigw9&ttlf|tL&u?7pJSqh;P!TFt|{#hcNTbhc+VV?RzHvU7;H(VpowGK zkT;UvvKE{_8jj zk@3>iMc-D(sn&Fm%G`Y5^+lTYQtOp#Krl7et^VSY%9U&Foo}PSmdpe+@!@{5y>Jxg z8}gt3Zs>H+&>Ba&&t%S_lgzzs37-S4hhI5&ClzhoG(*gnkV7xja;TN`&oL9%{W*jC zhP)6mR)d1S2&*1qmf`@W)F$Gw0j3^reM&^c{Yd<{ z8_i#5UD?nk8kn){;)YR}u)|o#2t>NYFLgJm4ZnHHt&^nmbw^}mvgp3+yI}-)+`XO| z*z#zD$nBZ7Bp$jFFa-Yin2;S#1KbA{)Tx>Y9@F3$(J*~ZXU-Qt15#aQIAvu1ct!WP zMzvUL+9BhDypwdzyGJONQRnei=c_`6JraV)ajZQ|hP}Dm&zM-MAhEVMZHfA#;?ZGA zar{gaH~5~yDDO&#As_MpxVC(HeHK@XQ*PNEl^o(Br&U ziHa{p$&oRst3V5R1jF=a&v1LkkDX^pN zXe7~qH4t3gk}GWZSH$k{;z2W!{ZHnfxC67pYW#Ri7I?XE8sXd$0uF1Nn7~ z6rOpc3BC+b*}hj((GkKcpReKYs=QKMuqM9%kDbQF1jWnBFpw*7SnEU2o9X%;bAi!L z_pb04vdI;c$shNVHqOb>Vn9wX^1r>nry{b7cfgNC7?K!Lzx>iADw8!Ppp)WiFp)vW zE}K5#Jqm`)a*;$1bwpgYMXv!%n^tOtD$_Zk>tTub<94SRn`S1fAr)DX!%7z80(%MJ z6pqPd;rZQOQpy}&EG9ZHxGb2?93%IaPcDAo3xam6P+pqJCiub~2uvC& zy7rWqT-#qobE2|a?7%KXQ>~0#kxzkjhDFkUR<(N-Wc7 z{B?hxt;fUk_eW4c-l^uwhTVyY2;gRqNL$OH$CAc1g_2KHy#^d*{HUR(NQk%nOAX78 z;cCfAB!z_IiyEMy54&*oaS$R`ol&adx0ui7{ zD5F@8_G<+vo76c0Aw$-NSaY0f0^z#&-kF)Eajte+ehsoJT}1?DYCxDymkW^t{R?J4 zQr7)T+8_aqDR6i1gF?|p4K}0fntCykM^-o=RHhP^pI7Y6U8ury6M`A1p{-`Z=|eAE z9frEmY)8hlTTG7pLaMtCZUw4vn65p6yoJ|nJXi*4_$BTjJ}X~iR4TBUbUT4+4A-Gk z4dgtqJmnRaJnCNlea3rNH?bB1uA`X6$2S^Ec(Os!K13(W}0>u_dlh6;bULe4`A7R#&r z?|G+`Y?kMQP2-QC<9Uh^1&)3ckqO$ANvXHBl9l#AhV+R_bzZBqg! zegWhrT*g1V40tffNUf}$suRZ8hTtP(*;I~e%-!&sqGx$y`y=hOep*LYQu{?%S)7~* zmMsnf^*U>0cY4ABsG4(?3y@W|`vvd-)agOBC2M@vy^?2{~ac8B5Raax|-+q z4mK7`w}$!n&rz42aq)!jeKPr+q%Rud-gx{1L_Zw5W_Vtgbb`Y1#|3S$c=h;7bIS4U zli+`=)KwEX>7XUi@n+GoL89^K6jf??agytdSmZx1j+ev~%67m#Pe<+xCbK;fdhrGN zy*@@+MGVaOLH+la4tMkiUa^{2Ne8~0Idv~**9K?rz5gpZC2N5FbKZ@V&zP)1gM`w< ziboqm_kQTKBl4a*5%Ws-8<+;!7?V5kn3cljBa;#AJkWE9qvhy1uw=o1$17W#X9}N& zlbqwa_77v%VUZc$aPKbuyezt)o|k>Mzn`;>tebX=tHdv_gIlbj@42A0ktmR|$LeJZ zofd5b+BCHyKh0!Bx;|6#c%`3I75G}sY8NBXbSh2rOwrH=zwybVNUe<2qu%pu#L9i* z_Uy=<+%8QRyx&T6LFD${b?R?%zrn4F#pawHXkJ09Fou_wwAV1BbT)=srv&^+fEZu^ zFabz)JN_Ow>G^LZu>WuyS;1=_*drr8x-S9W(u1z~Jjj7>1)H~LJ3r}wK>Dz3lOgj) zUsO!KL_)6ZXl7Lo~G{d1}t4JMH}d>I1y_=B9TVV zHTitndsr}`f&o8GQ27?_SL$DYH;$F1=TQIaae{W=fEwzyt(a46kggRiPQ!XfeJ61s z=602CM5f_BFrYkLj)6Cay3ymYmM?)pU$FINQUvg<3Ul*Bp!Bu*aU~nDsDd&Qe|!8L zvt5l0eDS0`#`BP)O`5B3r93nQ>MV`~{%U>M~T&Y}L3bRYU+s5V8UFPn8Dy3qz&|on`b< zF=H%9BM$6PW2l7R#oT1o!6^x|Aw^s!bAkTPV%%LRPY#TWf4$wIlY1C}fl+;Y2tu1*>MX{mBk>lYx8UdBn#!Nxg%+-Yn+>uAWYPX#X=IU*=U1^kvw zbt9gtl6j6iPC`@Pf?Wruuc|lBg^Ng4yEtWlS{9?TbLZ4c&O5U8Y3-CkI$}vlW0cF9 zc3EH-S_Y7emVrF`C9x`@s_rm-6~?6_%b5>8Ql)v7qFx1kvz|?!o_GC7bH)vy*(u+e zGh|}6E~gT6R7C;B@Sz$~!Wf%dcb)&kw>}y!En`ASMEA{867gEx2ox1Q?k_-^dt^w@ zV8~qLZSL{Cd5K(miO6=l8dd9FTr?I8wB%HXs=p6xyf_l~A!F>ZU`3K`y?x~M5aO`G(l}#5I%~^!zNk-T7Ra@ zQn<9q$--I&7wPqPqa@;m`rq0DSYivf?cKGLz1}};qk$0f*-TYQP=>HZtE%{UGd|QQiC9@hc-p~2p^!RA^}%|A%@hB z_!s#IwTwhe7~75JaAw-!Mt27owxdwN7(6~i*`kjWVA28%E!R}ROQX_NeokdFBsId! zt`ARKOuz?Xmif%h+XN#uhF)d0L9F=!*ib7RW=o!C0@M4v7FxiQodU4=+*xkbEW9~; z?vxRQ^K$vfu`t06x!uLSAaKv3N@BLmZNUftT_Q){pT80ES;Qj^d~+WZ;k8pjGGfR@4_KvU+kG(q$WHG2_WL|9TYfz|QIwH2e!tX$!{Y5dp+5@1p z`z#e1%boVdft81nsA%21pkWIcFO7WiFTR*47kwCH9M`ll?-3rzJgCp<7eH+>1fJw^ zCy<}1MBSzjT-7ED?-z*W>!6yGI!D#1A!}D>ytBUG_m;}=R=zM@?GKL46F`=dWe72i zC_KuSMK)&1uW;sncQyzGWD<#dc7SWYxY@o|$GkRFkIv(0s<*GD)6VrC;w5h7FZBt7 z=O|NflIPzm;h)>Npf?%(C6nay zHk0aB^WQo+x(slJ_zBbsYTwuHb{$Qc8%x%Plgq(xq_OtmT zFj>CD!$z9Vh3FxHX-Jn-Efff$Z+#EQ9fclV6$R_- zfAWm|ZX-TTX!ce#>MW(3emKq_70IFQ3Z1~NakFwc_p8Z5<|7k*t#ivE225r$SCQ#%hk_mqVc{qNfA zpPd7*OlC_!+dLkwgT6JGEGkB-nR{B^JFKBfd7W@ZT_l<4K6Utc+aE#TK^ZSk@ICWR@nw>oM#MtR22XOygC^kc1 z{sKfz1;BaL(c?OJsH%T-$H2%8cw5}FVJaglRjoeJ);ykUYnM|2dQk^X%4n7K(|~Wm zOC%>UDkd`N9#T!GvFIe?9E5d%c4w#?A@7*rW2V}H+S}{0f`oJ_pcI7Rb0tWyXyfCZ z<|?ZfWiRTiR14^7N%`}&q!ssC;<;&W%JGLxXFl$)!J&&9tTJlVXn5!;puii6yEN~r zHlS9h<>)7LsScAw_PES|=TVY^F;x5jUk3q5)YJ*VyF@JSys3r=G}z)qhJNmdrEt*J zuCjA(C0s0X$KY(n*A7Y|Wb^v1;XXBSZY@Luoj&eR=Dp&auI9v~Z+F3~719`41iqf$ z#5p>69c>0IjP=1#2<;k8jwPr~ksb`F0={w$LN;!Ga+ocoe=2~@BxOrSU={0u2AHNN zUB#>2Qd0FiC8z= z$*laQ)lv(q3{{PBUN#Eo;sUA z0fEdJxn9T$jX)N4ub|TqHomw(y|HezepR|q!GG}N!a7SP9=NYtXv?75yVNh;yc@TE zG>2)dXEl2IgrY3I0>InY#-Hzt)3C|5Z@D&(2+%w7c&Gss=SHd5?H+-fOoLQmXcmjI z^|Brxw}DU}F96{MCl>(hQ};5jT@>-cUk@{LYWF^4s=LY++u{nwEpAtp--UVPL-2^{ zN(yhTP;~Pd82Q$$!Zd?>?Aq4Inmtv_(R2|CWB|wWt70=@$g5HVaf3r}_VJmj{DoQA zeVR@DWZ+QyegoExmN2t?eb0<=G@3JQjhxqHtX0^CrGAvt+m|~(ID)RUwZYrbPf%!7 z-BAoV!eF9v6p7o*{nGs}H{?I@?fwPjaPs_kATWYPWL|yphQ(yaAm4|nL!-U-FE#Ge zsJGGlTW_>KowaY79Xw&nW^oO< zGcdQ6ZFAr6ib((8w+Wy7inP+2VfdyhjWlC9IcL#d z3%9%6B;8U^SI^8}nMffH`sksdsva@YYe78o%TB0>7=bNO+8(ND&fK5NGBUwX=mROu z{&E(SJ1A}}{+%b)ADqsAv>gB4n;iFetk&t=RMag2Xw!`cv|^P`pK-eSkPGjVs#NM( z&>XE%wxjMIEED$h?RIfeC- zB>Lt_M~W9{Rq>MdAx!0UN%hx}+Ncfh#Q$nfxIS+%eDZ;`YG*06zB*%M}Z+~N)aP%cJG4C>#XflaG_sqHh8?=Eu zEYN?GcG>>lcacI~yf8bwI$;kU8+WztbG7Dw0_(jYahUu)dvOH*-*wT4K3S#>&=a#k zxJpGJI_~50tMJ4 zTjRWm$bYe_h?45Pk7M(llT|jPpKL6-K;a$1_K5Ct&+rr5a=mt?K+*Z~b&eOvgZU3s zmQde=uf%tNvc6Z54C(*ZY#^E6M3VcFnniObt3&Hc3vA|5VhoTyGgX z+oKWu@#V(;-(A4}43h#bRvGeX%LZf)#>F#gCo1}WmH8)je=V;fwppV~XXVes^^b}lZQXwXd*N06n%`1- z@gvARIK zJ?DZB<$PN2*B{Bhv;5ujj}bu+Ep{wK66~67WEvt3ACvxI^ic)Wjg+T%g8Hs3&wBIV1lDtYJ3Jv-sx;k)oHky5d7i} zIGXwA=wOzLsDbSi9j3?z9g39FLiTyA5(|7nW|LukW9p_C`I6wimT_VgxHfW=G*u#QO^soX9oDo%rSTjRv|`3!!Da4lN8I*fHsTE}VI^S>KxJxy&l&t;7zyUtUw zkTXqFm${J`<~1o5hlnCr@J+X|y4K18Up@W!<&9)6Z@8IgXGb%&hXec223zw@mjfY# zF~2P4ec9K&_YykZkH7lzGXKs$kq-XE>QSZZLR4yDjCfFWY)}f|6D8IMz3Xn;4TmpW zuouk>`BJ8%=&DM+KQfX6DRA-16^A%Ab@X$)@}`Xih5IUrZHoO!6~)>>CMe+Rp0F=W zQ))k?NHI1m>ROppI5P1D>z?b1ck=2f(Bxpwm9h8q=>+mqG4^yV+ z;Kx(Ygxxz-bmonQCvd2*6Wg%$`yk50!1Fb6xD zCz@#->5(&3NQ_8f(+oXiS#IZjcDM z+Qmd>Nn%v`wf|FB9BjXS63mjPV%p>fPJqtNIymGjvF+a`_;{2$_*t`hx2V|0Vx! zKb296kz^VxA^$p2{-a*Z*ji0|v<6&218}Xtc3X-)RNHm^|(tE)!C>y8n z>2bw>(aSLgUg^`R0iH$}G_I*6-f6Ql<&k81WT9_USA3ljKg~G*y@C?O0Pg>N?&+ISP$wDlEQ1i1p5WJxb0=glz^2*S%1f7HCBV~2SW^)wQq?X+?v3j zT1&LJmBTY>rM7%N$ZaPm*`i}$)ZE1Lpew5@FID*k2fxKERFJM5^iVNYg=t3}gC3*# zDx=QdcvGC4&n6tbQDfbab)9JJ)j$Wpoz;}n3OZ;(EH!AUbu}m3^{rf!bnF3HgZdq! zgg;P582M_uppzmal5mnKrpZFwT1&3tBLp#)6uGX9^@W@#RlKk2j4mysNTDL((%#vn z%n*?)fNS{BMe(mux+WTB*cH}PRlCR`cdyg;reG#@rZsrBD0?_3d5CnV`f9wkomOFY zjf1#RT0!=SS&9Dq zj6~Sjq!Q~N$(7?LO%6lvO>>y2P_R?Q zPe&Q@lFAa)76^zG%)uX;#`D4P1rW7q8=m=jS=?`qT&U)`5Ll(uE$#5m+SZrMf|f)s zwX$6Oh^^YmyMw63s10Z8No47ouXJrST9NmL@E;(_(xp13_mX1s>Wx5Edk;gzz9(X- zaM8OL<~f69pwQicV9F;)h+z1HziPeXNC*s^Ir#v3{e$HLTZNS2ih#=GJuoXez?xY;s4ue zzb(yA&%j+ZwegIe9}w)PF)>c&?qS@d*2|Jj>W1>f|Jamm(DtCHAMFkjr)~{JNbkHv z(=zjIq-58mpk8=|`?p3FTXXY1vCa9riuvR7ew6jN zyQm3wWg-6G8t1GFVV(sQhusJv^RuE3Sk@+lQksbC)*V*pC(ge$ipjU2Iv)Of+2Phl z2$zr^tht_TG>frt$v=M3*l!=y&gV_3M=|x(WYKu)d&U!3WVyHzu+0B9|MN0I0^x{` z|2`v@r~l0cQPAy4@`h%`1T@svhuB2o^v`j69Y7(bdz@Y*N_L^&LL`DdS9`M&KBse8 zj|nRuy4A+{*7>tq?dYRhkM;lmH-7s{=#+RTnLwNkaba|!$ZiSQ_2YjFo2^=MZN&r% z$t5y$$J9UZ{zqoyVP;05N%9J^GqV#B{wTD4K}-!dY6RrS`VBjiG0#WMbzQW`(tZ2l0`N6%`eugL_ppFbxK|G*>*)P?zew2LgKk`1#048x{n zj+p1d=QC)vb}c*W7MzNKagyRn6D%lIEp*BtE<%;{$_yMt`P>KOAn95)R6RmTifb2p zV95Rsuzuwqr%EeVY%+Ux@DR1@D7K4nCw?a}^_Un4!~4+uAyfjgXZPUNb5~RCatdlU z@hrD~NmEI~N!4_jYdDgRSrfhdbVD`>&Fd<;dUC+!3Va8DWj$C`oh><)=Z)v_v8-}D zDOV<&Tm5uF!v$y7m&3nwn0j3 z>29Pi?a}0mkl^Slwe$w`->!`>ugMB*?C7%@b71mj>|L>9(U~;c>hPk7UYf^7pOM{t zX5SKLijz07$CFnY4%FHTHHN%KGJ53Wer@v?IKYcCTQth`z_vfGGL;~HEVwD1^-Z~# zb+$DYTUBK@Ak3N7hNM2cFd&4$bqCjDH<_QA5DK_u>>CS}`&0(oGs1kEn@TBzAr>hwS;2trMNf)n_)c!FI!h@CzcR zNwcDjelEEbBZ3bc9Jj6^eUFZ8wK*c3Yo?M+BHyiQh`=-x9=k9Oaa3@|lEq3mwkM$? z)Sg>U5ir3g9Vk@p@GDe~;Du_n~N;mw$2dQD!TN%@1tn0(Zt}#7lP9(S)osA0j}01BFy^A$&lKs~jI|*q~fG-8iKkqsv8a~1@EgDT4oC{rY->axCs zJ_kv%4@GG4GIhANJ$(zeBr;FbtTl%V75#lK_h)G{CctctCNRx^T*^;Om6yb`-5f1B z01E9NK_AM{D?%=T+iwWL_LE{jI4X5q>~sp{7kT=I^y0p)eLGG5T^3$y z=i?008G}8pp@Z*AF}d|FOKCggiGAPErdcji%4e#ggMD5isRO}~s%EC#bOA`OMt*xO zjab4x_$sZ=UFlO|6F0XjNKa1Qd}a%U)FZrRO*!k7+wUlNp*x}xRDRL3a;16mi_Mos zRy*Ls)@%^Lw3Vph3Jf5nEy5LgO{wWa-_XEZLy9t$b2;A42a1EtO{siIQ9yoz%XMpJ zk%YjSoyjoZ$#KopXa&p;tvk-Z^(5=DB8OFLN_@W~Fy~$dG@bB5iXux)i!XpA6gxD{ z6sgR+CzI$Ck55fK#~sZpHUiyiIt=?MTq%^>k(y?vZ)n6U zhFd-1Fy&2&!#VRC+sSg29LkWczs9pj0~}}Kb-)~0>X(g!r8D}k1-d@#irlt*8QKEh zU*DHTwivoKJLN_`!a}flw2bQv%!IB4o$tsUfYzYQ9J_e*lE0$h=o@T4KyCQL@Yp+r z3JZx+tj4Xbv6{DQ7OjcuxK221!(NeK2=Yb2+!Z_L6YKFb^L;ia_V>EICPcQ+GuhPh1nXFw!CGybOAU9bbX$K04|1C z%kfJ&mOU#sbJN8$n!V%20vp#Dm}>Akrm4n#nRyW%3Zt7pHN^|!k25f0GFAv%ggTUzPAlcxgd*%! zP#j388S-BBBZYCd#bBwj&`7Bhy8%Hd7;P(UoKINH-H}H&mKk$~CR*1sN_Nb8`3++e z#*%e6;X04GUm(D&vf_iNya2tWvrm&yn+dkbGE{_fX!MB#^^h0&yV&CHWnxl`(%h;V z7ex&gp>gOd5&z2M2th7h0gvN1?}(A7Lg_M($I?O*4ua1Jh@i=`IFOP0WwOZov;x{+ z)5hX;6vsq1^mQO3Og`6WTP__5)*P_6(p9um`^z@~WRy%S-b|cN)Ck0=$t`WqO*hCN zv1@Q>gWtM_KiIAl+B51EY9cXM({yNPCn#p}MH#hf3(m58kiWaHs7nZD{%8Y;_Fdum zqI%z;CV6$0#y`-{Q2BhkaMK{8Z3@k&N#DGim#eKv{v&atXUU=%UxWx`u0kA2yiQ1$ z*H#8r57wX>h!09EQq2O)m3_ADWzURen%t=~2)yH&YOHENF@C)XF3Zlp6D#(u=Qm|i zP}09ctt-Q14274|381Y7Q&}Q@0k*`DH(^6RTSnnOibGeZA~kGCM-4799r0e4}!TWARaReL6D~5sw2li)wZ=zEBo$UBcdZH@Ks| z&$urfB-7(>9XL|q4D&X+vszCvv;G1&@X{>}&NEPws5WPjpF6FH$H^2S(6~Ua8#Z{6 zZYylP5jnDOKRGUQ&F=+UH|si;3xPbVRs1my~lPukxme)}49cU~Qh+3e5 zI4+Z#dcYNcqxRVn){H1jpcz|l?HWrquS~@Q;_`xVsKroR(r#7&{?~#oKDLAs;X*uB z^i3C$dqUnd+sYR_h8l_ia+}=Df@06db__OBoE==GO(l};Z^@CzWoQ~$4)-GNQl`A$ zn_ROyu)o)MWy<9}^WBcN&|kaj-z}mHT!6#Ig{cZ&vR`$}XDT|bB{P}&&En;Pv+3z+;$I>O6vFf!yOs;d-5*ZDMwYTH{ zb~bO7FC=19VpMv#L@_RYrD0tU`ZKhJz7Pr$7k!K7$Pq^Y$uiKbKaM{`3LD&bu>GZJ zvRv*md3QV;S-15NLl!D_k#F&yD>^VbHcpSEtuV)DJNsz9uPlDng5*pf24voyo#yWL z+*BB0=ANiLKV38>AGSP)+k=}1LzhHB0-XW_x~W@V*iU~JAAb2~vB>iy-&ZXQr`Auf zQn{9Y?f|XnrM{@}x9~ACKH71o zjG)fsT34<7DkYN!AhV%j`Q%Wasnm6T<2fIgK*w6syfRTn`xgMN0u7m3WEILITx0f8 zz2qkqCaCt75k=_qX0&$nE=|1!%-jbMWNmlF}2>iXJDoDg#;a$jQk{2c!b}OSWPg1PR~u+BNnd?hY0IxcVEUO zuIkbDJhy|;G1BRWfTDPe?UR1)rpO*6jCLoNljhrY{YLww{G5KG11$?!cLP@3;hU{J z3hJ+T-;Sy2EH&$u;Y}U{d<4jWb6_2+6S_22@>Jg7jZfr|wSngnO1{T_S-z~TJnRZ! z6Rg;W_p7kU#wv0tA{ah+t>!E~EfEbaak{BWO)1tCQ_C|N)_#w@hJB=m61A-&jh zLpwvow~*!1<9NvPZ6zVhB`!8!i|G|YRD6ZHAebAQ`%Hf=bJ#*CU4lv@5)_tUVWb!$ z;kn1`*LfaaZ3BHI`1gMHIdgLK8%$jB(I>f2@Q4lUQvgx^VhQMs8*`>Plt3A=2@wPaDt%#6oP|u zIVnXBs^Hnk@eARnAjBGdACefGv2yGu$#VD+-9CG0|m<~nMWKN>jB@3AY7z5 zkX}^{A7hc4pH(3_8LEC3IaLV7jv+r)8xl{y;a={%Al}nkdUjqV;0KO;s$D1aJR9`> zt09tjPt8`Ij)PsW{pGIQ0mh&drd7Q%fG2k|xn<-w*t^p0!>a-Ae8TB!ZT{Cb*+S1i zE3DwyaDQ1FYvB=!M9UthGF}7c)kV6Zq{fylj&V5P#XM1ur$6iaDdtnquZJSp$pvs}J%~;Z6C|N~0*` zWc)m#Mv?Wj4Y3pTd#6Z;E*^v&s7wG_X<%uy*-~fl6$0QKVwsXbU2*d26`C~X zISZ0W!DH>FZ9jNsL^Tv{%F4-<*uFd(L?Ktwlz5Tww85NPhVl-R$YsKQgepAh+?cxk zD&;6vFzTlBhMN&%tDB&+uqSDOZe!#ifS>T&_r?bQQOVL;uzIFW?2EG+#R*_9r5Q<+ zxo1?D%&EE0L#xv{H9x6TPFN6Pgu{1cf<&B0Nt#gHj4G-5x143NHSae_iIAD@HsOm1 zwK0;T4GxW3pdl@EdtRMHh+iZ(TXb%)&`MPO(WCk%=!dW(qcS_b3|aRjtH;HG4M-_a ze3TA!hl3bP^mOyuVAL1?gKqXKzmcIK|LSuq4B?|a0J64MpUkGM8PxA3^bj#oz@<(s z5UIjM&VbXfH_I$mVmd}9t5ZeO#DUuxw>>!3{{ttYh6=L~bw?z<0|qLv8bqNUj*YWG zuH8~#gG@wd=NyyWYlQPcofV2mjB>oleSR3m%-GRHj#zABb}{ggFDquwY<7;pNp)6s4R&bc++$A%w>V0(G`nNA%<+`c)Q9*yWm zT#7mJs&>}(Nzy5sf_R(Q`SM9Qkwi^cW|1qKRs3RMy9M=+u^l$t+2Cy$w93~uMj9y* zl>Pg}ENiD)ZzY-M3+nk){_0p2kl7!VXZNrN{}9>oKmDpNw#OUY2l(_~C?=UpU$biB zvWv+X`dNEJ(-y`0r+9lS83epzpo6eZa>EqGA$BM0n$GGpsr;hQO~nzJFt~c1krs#N zHBU$W?kxjIWTPXV-x56~rs|v=6>e+R_{cI?zVwz%?rm#R$g&ZYdC(!fI9)kAf>7aX z*PFzw3PDVgS*U>{(JNsE*mrxuiK37ycW%y|^0ez4pQze_Oe}F`ibfV6KM=eXZZhDi zvx|m)TpZ6|@#6H%_U5+1$}UCn(My8U5320O@FJIu2=Je$+49(I-f#!f%DO<7pvQCk zMLm#VTx48SEaRO>VJ!L8r^~!b##1$|JxWuS;`x!tUaJi%Mc)jmEkmPUfJMt62+fO^ zx~Z!*)P%?M+?lCH614~>$Rr^s*hcQhBQ%=)0DZET7XH@Ce}X?*qrK4tOU|U&JrWSS z9<)XIrlTZ=5H;UDmHH2$3ttS z`cdm+y1fg;={69{uPK|Qa^MSxcO0AH7Zi$ttop4GAeVe=M2z&nXBHz zyB2;^$U8A8*rj;#<5^S0kOJDmpn8%<_o0x(K9VJ~5g<~vbIvE7(a{##6Zz+Vi8D4( zIirtE)rX9rO7C(7-eKKxoe7EAWMQ^5u6Qed`4^M3>GJbp{vG>VT z3QX{RVP08N#LmXS&o;IP*cYbYX}a)#lf{A2rO^}gww4VcUPs~O^0>ZYblb77C;pML zqYI7SnQ!ME-cC1PRDpIxolZwutf8GBloLh~r$5vt$)rsBHBE(4QVI zh$5qUnVtb1l59$L{Wy?y-9c+EmYhoR!AbOEV1HlXMa!&l!1~R=p_Xn$&|b-h$7t!c z4||<(@5-HxaGq4+G*xom>jQwjCzAOs@%G03x~`Y93iS=X`#kfj5nQI_Cz>uyj)EIh z6n!EL^G}@!*^i!T9hqYA!%Sn*>Di~}Q4SFjUZKbz)R9|x#pIv0wdQ3qbXtfhdIyd| z>+tV&^00pjf1{a{y0KK7|0;*35{a5E&aZ%&xwom~ru21zMPhxh#ZD_r3I0FU$4bMW znEKG)R}hbI!zAMppNkJkUIPW1j4mO%nqQUm>0iE4DyZ=j?01V=WkgwzF-aOom6-_J zSWh8-SY74sV1jyFWo(*{dGzz`;{ycIysh#@MCu;)u5T2OSbra72_Mb?v3wsf+o-uJ zylq|fxh>Ep>(!SZMQ7mq*@Pokyo-+x55iXhB^p?`pgZJ1FlfV}yNi?fs8+fR-E1Kx zluAkvR`pUqf_{RKbbiW@ZRUb9$Z0j?Xs{&Q<;g zTK1yoV)eD55NeF_m!**|E=0OW7BopPt0k*Esq{tVE-22s^lTtGcrX67T9AKh3gU?& z*Cr(KQ%~*!{#{X;WNvqWn^pVn`47wAT~z-u{lH(b4S%i`zK7kRhPTgytU-SL1UH?+ z1!6bb9P_J!;n$Ofa?T#vi{*aV;xbLmClALkD?(^qQr+a?HuVsym1!0x$at_{9komm z|8b(Wshr&`gG-Hg^Qybv55x4Pxi z!5HRfA*Kjyr~Fs&fIYWyWhk%vX+tH2c}C(pa4q90c@&b&hxu-38D)EHXn++T1sES$ z%`56XIHKTwUrlX!sO8fe`tGQY-K0k~&n0y9fZ7$w&@QW(kq96!b*qqy8^|y^jO?<% z_{Y6mmeWS^fi$VH8w9G9MLSZ%SFaP|PK{%`;qgEy5i_Azv*zAJQJ#@`d7_4XJA-u0 zSD)YWvKG%lHLKFue7Dmgj+<472%1_mI&j50)u>P%oG&0pcEE}w$S=*hCMLx-Z$ zgbyOMvewzP5DsyeID_z5A6=l9kZ9)GbCa~tZd$(h8l5^V^j z>C4l5a8YKoVgb^HMJWVo#uKviz>S7t@hDmDzTTEgk$QgQY&bE(M3bXK>#1&&Q$J4w z6?35KZjO${8mI#E#Qaxta!-{u>%6F@0T3u6N0Fk(x`BBAO;RG-dzogNDs5U*)Rzp| zYm3GymZNj`aDN@;Z`u^+lk5T)*&TKBVf5rdGvj=KZMX;2u|8M!;KnZ5E50mc@GfbM z(^cv-&Wan}%<)#_@Fq;@jwUqHH11t$HE?pCUw#k9QFC}Z(50j7ENF|Ak~vl7k>irb zUf$=8Qj{AGpgR-W*hq&AUvMz!=xN^0h zsIEQQyY}Yr(!y5{>&Qqc8tF6Ii_CC!#u4Xls9EnZUbc{}U(Ece`u^V}QM^p}1$cEC zBP05i>Uo#cA3bzW8^`M^8%mYq67O1tS>$%ugvmSo@2{zH{{rRResNb*|51x;6CE1Hk3z8_JN@UGfuW(7D2imKbmE&;Q0G2 zM!6*~z;IW<$cHXZTrP?@!D|rLHcW%lCs`!c*P86XZ6-R54@jq<-llni!2zafTpOjl z4=!MgXnZmVrzO4HHFkS2tdTXJmEYZ&R!9*uMBQ&a$Pv5-igwC6?|kB<`uIpdcCL0p z)08hQ4YS6lt+**|Lxv9{X)QYJ1g59!80O0d%0p_Gj3AfzX%{0GB=S=SR$e#;h}=?m3nh@Oe<2Dj>N5=a3RhFkZ8%fh z)=4+lS(;S6=fstm1_ItB=Qk`u`i-j|f7*>YS6|^x`yzko^m(*YunUfB83w1J=TStH z0~kG)U(rY1k;;+FzoleG1KSwi9Yn=a!}?;^HW}FC*`GRrE;TvxKeV9)yHi_5Nu0Pg zN~>>mDZQ46O;))RHRvP}7h3+TOdfv{lLu zn5jHDD4yVRNL+8P4f1X=zeD7V@k5oPdO<}H-I$PrIKe3M?$E*g^LpA_Qvxc{>6$+M zQlp(@w?%xipz*YC*+T=O1+-L~hds0nKLB|_W2I9IrVCe(kJB4_hwvU=i?|w1U>O8H zjR_=aA55WUlWoM4u_Ws~*;xwvogR5z%<_#@X_n4Bs%v-=ERFM;s;ZR8$GD7<0K(-- z#%Qn_+GREuE-{!~6mUCzV);>>X1t=T3Q73x2Eg3I)nQH)XJ)12twJEcJe{`Zz+=B3>z>dW(YdDCO{|ooCK`?Luz>46WuF~ z<$HV~rT?1(%XvR`bWI^T`?FZ9(*|D|cNqv!!nVdNZ1bKrP+i~0_+N^90dh?Wt?a^#h> zS02p+XYJPX#}zy%>Ca)YzP%8NM`(XNzq@6?Q%{6HEjZ%3;OWrMY12GuO-(WL;p~}N zP`#U!mxyOz#lc zTbj=&m@%qi$Q7IXtac=5b*1xX^q6E zD)XWCS}?cQFY>goDLPr2TWM6~!{*YS(X^`rOK}dP1eOmc;dWYDlPSm*Yq;@|T0I&O#L>p*tp^KPd8Qxy}w+t=6+C-TbkhWKiGTgxVV;OUwm-)!6EqI?j*Rw z;2sF>?h%5!JHdlH1lQnh!QI_Sa0}$k&fe$lefHV+-TQm*zVpuK{vLm@X1c4pYSpaO z-PK)HU*5!+^_gbbAltnalI}FV#b+|gnc#zlAa)JWE%6XSTx4D-Oej>zqa>(kZg&Db zA40*;uKLiMWOsha_UvDmB-A}fs*0d?MA@A=@p15}yQDGT#L^|?bT{bM0izyPV?Z?h z*V8Bpv8F8egE_A%Id16aMCg12#OdHiKNFux&N&pi$|b62tQQ4Trnv5Gi*%aY+vCug zNxOVRgtsI0Ot3BvJMSeN!!s{6rgTA?8qA~Nd7c0xvs<@iYJnq-y)(#LM53T;ifYsm zdkI+`RJE2qIH^q4G=MdoH?tMSNwY`DRq6JVz8D7`Vr7?v`2{nhGSW0Wt5tAJ7Lw(J z@_}Q&tR`>_>_HV?ftBU(#i28zga7s}@jrEJ=TZ~4Tmyk(_{!+M8R?Te0yAMy^+mmH zhb)s?rgicM;Dxt_4Z~s+xPo-``OB@@hEMcQ5RV6T$`h{l9aoFxnr$*0Mzt`S9fmUS zcYRO!`d%%Ue)l~dPOO_@YPEw;{osdJN<8={{%`a57&2$b5-89Yb$7l?y(N|EPvxkg zOU+4A-d@3+591~GIRISA{mj4pAC8oglx4ArXf!Yu=>M4e;Qpj%$hdyaG{#u@R>CpZ znR+x&&9s0Kw5{lz5QIt*T#cnPIFXrCHZqX2j18O6SR4SoDCq8%#0QFX35mLd9!+Ez zv~2u`h^Gfq&J(v6^9J>3yC2d^LSj*~ud^c!kKmmGwykB7k_m7HQbhDn3aczKJ`z5N_WmA)x#6+a<;b`$R8jVinaok8F!VOIq{ zuBZL)(R|yq;SnjDr?It0MnoqL0azY~h~enS!M*9!U022wVb``5@E~XZFJksT6I$k( zdUb4#n+&0WEIA0Qg+)U3?9$>w|V$=kox2w;Ju zOU2dTQVhYIcZtqn6nKR<=%q3mKwe5-VnZ!}s?vz@Tf}9d@V^sqSu)fvxrf2mQiu$# zFhySEf>A|hMR3>>`>3HvcUV(_TnKd2nS)ac6DT|KEAA!Lbn8^#j4BmaFL9FA$Z*u) z%PslR$dIlwW1)xpf2aZE{3>=t(Q1e)mXEM$I6=aLXO%3$Scl4r$0c6$1*Kh4!SU0; zB5&W;{|({(;`V9i5=N#q?m8p_I1pGE;rjW4b^jgQ6ye3@=Syx+K>WqOM5`BSDHhhc zyWIR}d+tVWx!v?$wq!ey-IMR3i@hxF8No*q8|vU7+J2%zijB~-zG|5_#_yf}#VUGV zvFRK4;vp<);|b(L6Ya71TSl73eCxU0(xHCAF2px0i-D>X#Q+-Fa}HKSRj({aizDc} zoU{ZG#CqgEy?OdeH)8JBf(bNij%lA$P)(AV^x%lipN&{|+us*5a2qvvswEOtF10~C zXSMCt)OV!Hc)pf6=V}tap5a$1MQb@sFPaHjxl&aB|4ReqRSkMuP3Ox`@nBeKv<1Yd z%z@}X86=uYEIQS!96j18Dwy=;t&Z0lc(x^Zi?!fJHE{Gabj)+&) z_wip?4}t0Q+G!xM(7q`+E(B-PjdJ565PWB|SC+-?bM^{-6}5PxogG~Mf1Qu0!^-NY z2Gq$>I84WfrapEa@XtC#5dJ#YeCZCgN0X5k05AgE8dm!Hh(od`>VAA91a`CcT)$(V zX}a;>?$_K~#fbmcDaKh8ot)yLv8!I-9)b$F1p|m@*P_bDK9hk28Xz&1$%o63P)n0i zm#+weL8^pKAD&CFYY(A~7~vp>M7w&LsJi<{rx9daLtIYGz8m}!u+=}1BdVf?-2v4O zD>)=3sb@}%@#_v}`w8s7Ibs>~D+%teQ48Lzon9JTcRh1eZLJV`^8-+&`qz=x7+ODp zM!gpi&?5Lm#gJHM8zsZJ0T@mY2#~{uQw$Pb5rqgD5$5~5Y-${rx`4u74|l4PwZ<1t zGY-qoekGyXkX|xH1>-eXJn8#?fE>>v@JHKHrEZ<{YqUGQ+4`N@c3B|-8>DLR$uMB4 zV9N%PKI-}ygTzhu1|dqI{K3DURP(WOE0Bcl!PcjMy8hXK(>rv%B#U@BAp1#xi=JoW zPl0|XM@u8P6II}d$Jg(KwM~mGBX<;HbpK;lQKeq%XWg%*Qq1JU4bZX1&hDWPcpvl{ zMc6ieR{cS~I&}kEV$3w$>|xd7IQHRS{FlE=^lLX3QYkxf;!u?vBtHOT+4b?>b;CX= z!KlBB^HX|X+nfi}`JVZ5bY0*bCyAflE6YDiot|ouK#vaJ9pLia%U7@9!3H0Ik52F> zDtO!6$ZAR_Aw~~9<%3FMKv7DlS6vsbgw}9+e-D+-J63AwZ`y?7nA=+LOq42Zj)4VH z43wjooNBzVq7*DxI6#L9jO}}z&}NOKX@%iLdgv+bpy*@A*QUBqs5Ua(=~3GFK=~~M2s3aWb&!1^x?0B={@J>7 z5B<>ICXaa}N}k$y4-55fM9@LZflsP((Td;EEi6f*JHBy$Klf+%pY#FW8|OX&y!7O# zhxwPn>P3oDbambKE%Y6c>6m21$-a3D?(R zf0Cw)vq3|eTb02ABu{PF+P#92&7G00We1y1AAvQH>}Y)Q#mBiMiavJ88P$GS%kjp}n>UN}$AR{Yk&xy&Ymn_+1j#21Z?*9oB zEE(oZTtMH7qTEtvD~mKQ;Qm#e`$_F~&@L32n9Xx{$pq`s>Zk+;BNrqY6}H8PyBv8n z2=+uc{^-CCWf=g09*mDF0!`s{tg4#g|JLsdEvvh~ibOtkti1kSW1#=yXLalf<7wlgkC$aAz(G zwD=WZV?vMdd;_1`qwdcLm#7u0UeR#?|9cx5m}6UMLcE#7PDrI-4Se;?efx}cdK z{{eWPX+oP>`&2KF$MGO0`oh*oQZ^A+M}tN6-R9a4fPxH^8S8A@dX*Yq;T|@Ty?J_< zF`{4!8I1YIAz1cgTLBm;qcO{*87`@j7SJrWyan_1Bx~nn+}sX(2M~oW1|%{S)P1%W zW*w8DF?DY*ahR@R(V}1k1?`vH42Iuf$ZcX#odaOiU#cZ2&&)__$&StQX>cg4*d?Yk zNxSl?lib?1E`;4#Jq_wo4Aa;i@*dCAvZN5=Lic?EsoNXT>1C<9QW%Y9@<`aRr=hM^ z#EwNO)}}CJQYhz8_?iS)v*8nbUG4PfP};Xksn;xKOzM*4$s4ShAp|#wM)-wJK!c$1 z>jIe1dU2Fw4^yM!Vik%N8js8Mkbn|71&jqSO$;kY?2GHr>?{cvVir7$`-!C0S9&=| z^8z#&$B_`pt_--j@=HS*spHsqG;F0tc&g2~Y>imvcRmj}_Gt*nIk2UX#ua5vaQy(} z_GHUZy12EF!GBS0h?fm-G7(KY(L7`_0WD#Ja7>5z!#y9QR}>iCIFk93xZ}7N%cr&b zWa~i;NY$p}x=~K`$%Q2x$MLUZX^V%TWNoZGM*O*u#qL!UBU?GHq1cjN-%s2y&EPP- zm~eSs;|r)H6a)6Km$y1GKUCd-^Oah>dD7YNmiw(s{IYe^UxqAD60=#11;01elr>m^ zt40krqYM+%W4SCQ@CzCW=8R}s#ff}ie8ZoXx89}fRwc+#a*|FqNlu$U~jz%8nx?1w^-#W(DC>#uk#DR!Svuf+U;+Deee zHXBUYqb1N~R2doUDz;a7YHTJ&8g8CQVIem%WnR4vT&1mtT~CQn!CXP;w^<~U2^AeK za;AuN)C?QNax5DZBY?#wk9SOg;oD@}!=%&Zj8IWadBqiO9m=4fp(nfYf*d)2I5{Vo z1uOw$0Rz|{HLAOitCuLJPp~XD%?>N4Ifgs8hoHv_(17Vr<#f@?3%P8=HdAwADt6>& z)R^e8P17V(OAt`j7@OE3VQld0yd&(o@(c*hcW!TAq-AC`p+$mN*Z~De%->KD5rcQo z(=03~#QYOg;?)QOT!d6D{S$EL5KROWy7sWx0P_VCUdL*Qv4mz;J@h-;Wk+-()tgx% z_;6>IYjv&2n^lh8w2ChhxUEw5@TL!M{vYq|x}OXj|kvDoJxiixLAEgCeH z4HnYMp<8zKcK2?Ewo;KNv|9|)_9cL^fCY{?+GjhHQ<6WAkN|N)i7XmxR9$#R6DWZ6 zzAT1<{T#zgO(KK~z%C($-i9C;qf_bS9{`GkEZGvS@58p>Ifg)T>>Vur4peeVf(QZ5 zzAsa6#hee+4oXgNTYi@d$sAO9llEx?az`8--!|s6;+L7;X>K+3d4}n=0awBWe-}8j&9Js)rW zkO#?Ar(gi&#D+A)u_ce3OwfcSqZGA?*T#75kr}X(kpI>{Aag`3rGy1l1-qnZxkDFV z@A7T}*&6)0a~PYUq{9M4AMKK^$Ug)ik}f~={)f2No9S7NI_DI<=bzo{`pfPAZozQd z{&VgN=hnpo|2#{%6NT&_xC;GxmICqXF8=rYF8Ite`PF2&l3(XCtf(@5)XVk$`}s0{ zc65rP0%%@^sC+Gjjpp}km|#LlFH!QmV7TVx4lzKNw~okv)1FHCy+V&QMrdQC=ov3o zkq~H;8=+@eD(f~aWSR`e>3@qv6qr1TnhY|kk~GC5N4$|j&T%DFOz~SMpYT9@&;DP_ z>mMcNDm9}c;J+qB&WA-8O1#27{bS9C19I@3HCjD;obq<3Gj|p6>+~>#F2XGKkRC9bGiI}|{FZ@gpf!XO2ue0Q=>r)`OS3d3X zy#G>pUwhi}W5)7WSEJ7@WXVrBlRJ-<49RQ}ny?S}G^Q&Sp?64<$?{vY-!VV!)k6I% zC9LgeNF2+XqQz^2KMlz)KLOmg{>*;(bf0gKa}k_g^zaKB3)mdT!X@a4dXG}sJ{!Os zfbc$dE~ZT`OV z$BY5#j6^}7^0!$fQbZ(=JE;|EzL$Y8iOmU^+9Y)*T?#kxVPAq(v^Sq^7hqk%yPlgf1Gk>iX|^9874uL2qOZUpc^9E-}x7O)nO7*p^4)o z35#*@4Ko~}SlDX{9F={|bN<}IYA5`|p#B2*qh!$CryN3T7yd*!@Q$)*CBLIYeb>hr zuy`}CA^&7mk@da4*rjX&to{hL#HPVe7bLNmQPBB;nTOMScK?|NtjJk$d6fC7A8i+lZ4OW{+E(_MXp7?x&mN`kb+a&>AJZ3)3@yO@?FHmM5 zuecLYOi0wbTY7W0{+LMcZ3k(Lf^3rfO%4HnP3*vq`>c(bi*Y^6mt=*CzU}PvkR2ZvrN5!J~9@RTWGxQcU5w4!mXaV(5`NiwfgQw0DDTY%Vf z(36EWEw5_Fg^;gAJtD`*g)+x_S!8z1V@cY%MBI464LQJ1`P=yn>6eJ6z>By`!&udN z?4a<-O^p}H<2Cel&ex{cnv<`2!MN^JhHNC_0{m6Rr|!nm+zSk^L`JM=6{n0htXSqL zt1mu^jwWKk#4lF%?3oBWQ<7_Om9=J#abh1zA8Nw8m2(aaofaOGY z{6aiYO?%DRo=Pyk_ki_bB#C|j4Gv7jn>K=;MR+k;TuYNjXMnv6@`&<5381R#8yK-N z0h3m~=+eJdWbl)wm+Au_6g$CK5wA|Dx6D7*_r={&HyhX17L7)%pC$>Ir1uYoKpQ^q zAg2Pt1apLPGi*#BMwV!&M~V;_zTe9c+@B#j6a^Uf0c-RRvuWo5hQESWsTKK35omv)xr`zf_a$)Lfw11;{IKD)%{ zgeAPIyvCDWJH;e?vQ?-OlQN-Co;Q8EhT3&1vYF-qCk-Yroa;-#U zMF&pRg%Mx1?gOJ-JTHdxs@)fLk*~;ghVktpKpK@zGGd!5D2Opm@ZV+YRZ`SyEmkSB zW~5QW%$jo46S@dRh_^c=6y6gaLla*1QV5jfsT%{qtEK_%HVrC9-mJr}(AoWyqYh?< z$L>a_{Vhb51=A^&)@e<-cU1{MVv~JrdYq~VC$!nLm$bwrbLWGcL{&9nU}Yy}{@&8- zE?d4ZgcYEO3nJQW9XH=c z>4nHA)P*FQaniZyxxhyUEs?9VP&K|)3f;3ecb=oQE}lwm(46fs2HG3eJ03qciP+}J z5xFokCFM{Lr?hfUg}#+qu+7A*YWQX`nt8@Je`I12K7C%op7`hgiNBsncdh zubD1xMcM_D`4S5!L#PM;1rDp%=Bu{JZ%>A#Y(ZkGg1Lg3f^MUd6+cO8AQ&LFo>3cM z`73y94 z;P;I;nkxxeCNJ+!QfYCBI+3G|U&Uc-A7rTWbX(*ajTFOS0%v*)@tnf2J@l|`OGd0U zE0P>{u;8wJHQ2Ds!V9jkucaZ7J!1zq`N>20y|LQJ#=gf!bh~VT1E>J-UA&fGAX$<$ zg9wkzg9SR}n#g<~%C%uWdz4)ut$hP8BsrtgK|2Icba_Ps7c?Bl(VjzVN6g5QO31C~ zZvjh=IY=zdeNoCSHNrexB#l3zpIe>p?oF`L>4S|2ipCLCHV zW}w~p$mU_IyK+LVVVF|np7~UN9L!hiGs|`MiSOIi_OYug=z|(dH$n=i2+cG5G)W>` z5l{!527ACmFH>1W-T&W+86PA{1-z?w~Jo(%c9K(;g~9iog@@?wEs$O*)DA>QV{O()rV z@dA*o5NVG33N7U?%kPYXz&TXGq_tlqr6pD33L*kRVx?@CK(O?I+)!XRI)^lfH3q6J zOQ?}i4b?>Ne5C{{Jr)3cd11G zDir8udeRzQPOLE4DOe%+H;~5v+3NBz1OO{-`RT$0W9Q3`5?O`?p&^F_pne<1dofZk z_4Q<5g~Ia#6D?52WmRds;=T6FV4)|I_4ZU-61TI}nmkbx*Vp|2284tVoSd>5xT+`^ z3v44x>alO{-)~(`Qp_mJCg-DsbXhe@sssD%28WG)|Elq3-E(ENcE8j&6dNl$4ad zE~n4}(TwXmn^Cz#xBPE%i_Y87_2~{@eDePg_Rp@!Qk)3qDJ1El&x0cipE(+v^NKOJ znPGUuPZ#=J_~5u|*b`nmaRD=DpOFX45y0Gy7edtlCldy-wTJ|N-+B1uMEhvSy8&$% zRi;IOjO|Zb9bb#_NAz-h!$i;~0$^bgWM1Nk-anWPATHkq%#F(s^K%(->Fn)+6mRd zki&0?tw#HHdqB5+B$N|+{_*hJbAQ>Vg^O*AbLuXO-j?HafFKMrYs!h{tq9vrl-|?0 zwB~m+h!fpf1jNx!_bibw3oDs#Ns%3Kvkx?S62T`~(u5Ds9AdNBebWCY${hVx-5-Fc zIu#>IiGz7GJ08JuR6VXVQ=$xPQVz2(1dy0;CWyBLq|fX*t~I+6ZO3;;k-6<_1+u}DDX^D+yGLNR&}6>wrdJC?O|9``NIsxX zry~~zQctMGO0rN=zIygIllad65Bp-bslV+)L6$GSKQ(9EKetDI0Cv%ot~Wk+hB8>I zb8ygUhWPlj&~!K=m~+R8cjIjRg)`cJuZpk@S6l^CMGUZ7j6FPBrQW*mli}#j6n92F zY~nB|hY}yEuA#%l;@|N}`R`Ed!ew}FdbJp8D##~qoV3pG19PAK18{oY{-X!Lf(ZqH zf`NfTfP?z^2LM1}0Vvo-RlXUKvxzwQW_MyL$4;D889HwGRQ^~5AVNXtg()EJI3nzE zh$+xIB)Od@Y) zma3E;f`xk;|Hl0}!*jZ!%;5bA!t5S$iYesn98VX%OLG{^G zEps@o2$sNFiaZQ^)Vo76U#Z$82pR>JZKea%@L?8sPzy@x2Y_+Jv|9OHFC^o$@ElQT z>o^m19ieXk`X+uwYJ-AqLHU&CL8f6aEb+?5ig6Z& zos-3hKGgu}csC;kLnLx*`58<02fD7AC7j)_m%-}NSnV#%0Hm2$%oN$(XOx{XhStALMFO z041ml22NcNbORh$5=nSvT-&mKj3@NRhnuf!?Oy-f%VWlW$km&(TN_x~tT>)wx6apE z+<9^n7wV>w-3`cK|6I78qtE2GBUH@lo0ow#NFh=c$2%G0c$fGBL+#6cE5f2J7?l7X zTvWA_O2hPJG|!HsOkuHGF@LcO+351?kZckH^_Sf9DgDT(sI2J@n$a+*uUDdN3>}?m z32Hq>S;JOuDUHMBiRmeDOp7LL@ze(l2O=0v1s_HPP@^PpfMUVmG)p189A_QZLBxS0 z3f{5Oj`RDXkvxjas4t8Ja-m$LxahH3Dv*=2t2e)h{sW*1pJ|}=CyE#jcf!s;0JDaF(*f{rW*v@wLMbfG@*O6`jEGue3kG z{;HN5t1}Ls9zWR9bt~4%Me+~2htCM$)~xtY=I4F@Iud_A71t)zl|zUUi|y91tr z%R`MJxDyAY=g#*k-=9;BcA$*nP6-Ou)4%ss9eeX~(uXTR5VuJ)5%z!7pIPe_4@G3YA1BGPG7{8>Sq za{AkaG($3I# zFMw6Mb{_lS?aVs@&9B^fSKXspwI|7d=VnajN>*g4Nn?&8`=~+{4ZJevVzhY&G4Q(= zIhSl@z}i7UwhP?j`Mdzd(=F6m#R%ZqisYd`$HBaIFh@C@w1Vw6jS@KUSec|E4;pm1 zNibhj&_B{ZkvZwJg6ryBCd&s~Lp&^eJ@oU(I`g^>->K9}Gqi{=sLu~O>4=}!(sQ+` zl=ukJW!#3>Z#>z zVrReO=a(p9s2wOKFmeW(G2@L`Sf!E|Y1!eN=92I#WtjH2IVSWH;J9kEOig?7cHqPbXvz#!Ok>(H*m#xlI~USp2ohBj;vMOyN%t_ zg&JAFGhlH1)UnrL{FWokc=G!h-E{J|Mlh4ELt-Na{MN@{|DE=P_PtEj{<@PV5-tu|U zd65q8cERl;ACX3TrYdnwf46~d&Tl6#*oi_wAiE{@TMor;5BapocpJty6<}%w|4;<^ z_(a(rl9gu8cVK<8(*l%Uf*E6^e(N5-B~WI{WVr`Hfu! z&pL9uV#LVL=D$=59sR0h*iH|uci61GA~zFm&<{cNy0SNev&;r>x}Fz($F8ndGryY3 zvLVZo-A9K4-1*E(zwq$>Sme3hkv3!?AviCNKxbz#Hg|UqSsUrD zmw+Q^R{fE5QYrfLe`BtfFAsh8k#~}_$BM}u_xqy?{?g2dv1(;QTmRN+-Oo{KHBcy4 ze6~}0@exD!RVp=(Jr)|NRUFH-#kQbTSpH-AvetO!dvtd7P;5+tJd;_VXEO@xO_`W5h&>Ezcu0H!3oOB|m{733Z?-u`I}^ z`K-h>Gx=@UwIH+@ZD6J&z6e_4>r{Dxy5lI>TW)mPRrAlXu;TD$B%+rGGgC=A@}(Qd zgxk-~Aunv^uP-dPd9b%9c1LY5Gzj9GC|&#R>S!(}a3bSy^H{|Rpx!|n19k8NU~Ln% zw90w(0a;rCf`Mipc^;=+nAVL|E+c(aq&=4$BY+TZVXf5V-Yx7INymV02Y=Av*`1@7 zQ$K6kmEc0Uv{WDDDoXl(p^mPo&nJwStG<=8t4f2ptO6>(4UM;7Wr7PeG>3MM$lZ2- zO&dL2{^qvTyW#02{l4ey&nc_r2f*Xq<^cEjG0C~(z4FNO_|X8A5!`9QXZN+4R^?>l zj3v6~$o84*j!x^ZT~MWv&!_Rr@@z3&RCUWfX)VZCBI_-U9vgoSG5&T5%?0ICW|aC! zN<_)L?m6bLW%!9_d5qDf_7J(ei{_BALQHxw;&X7haH5prP~Rcf0$bPm-qVAxxSsp! zWjTNpx;!OImxW<}B%Ub=%x=RWr+P6wtIO8u;-obn`5}22|GTzK83L0)-%v7zGC9$d~43T`% zRqF3gN1ZH|G2w_64U$Zrj7~7E1ivK@mTd*QMv=Y1gqxtAFG6Me>bPT;>DR2ficOb} z7S2X3vP>l2t%Al&ExASQv;M`f8({T9NBn(9ZZ9mnVNCOMOgfaPQ%6J>4le!C#9Jun zb#fUDt%*pO!#Dg*!34!Q+%Yvrov=o}yuGFYtpqH#Y$BF1*T7i4aupvPOtw1Cs@@H3 z0GI$(wawENF(fUZrwhgK`3q=D*u#)e0%uk6M|f(;FSTZ+zjs>q>r~2?DGym{l_;)s zVu)j;N$u`u%IF*jfb-3H_dQV=U*||KVzBGap*c#N?V-$vPbPXXV6>@Bqnr{guF#G# zHuuGES4O!#3&M?UOX00}W}=<3sU#x&?HL@J(~`$zrDr@P&Kg%PeOvGHeAT`^rRriJ z>YG*B=|mIl2cP6h*?B3O5{fu$b9E-*TUi^zPqebjLaJ)aP5Qc5yOI+|P-2-2IN zREnBTwL4FQ9?g(#Y*RR|Q|l~KK6`j~L7BS5I;mwF<_pPlWP*G6Bjc8m)8d!8Qbb@7 zL8pIFe#D`?G4!Ne0n==^**FI0QdSB91t(4!T8~?fA={W?pFa!oSytrU7_HO_*hq53 zXY`HR_`3ba8UYss%MMx8hhqQ*?&&S?Li`Bi)n!=`2+;!kOY+ z@Cx!V6NJhEC@_QubSSsxJWkH0XArr5OqRfh(~Xg^dosO0qA; z-d%P=TVWVc*Bmd*sXZHZi2Xx(wubKrJNHBlpBw!U2$&Zf5+@q8^Yt>VozOXk(^iqS zMQhXJV3#l)FE7+nmFPfWpL@8CLsQh}~?4)nIhx z9!Gz%b#uPH5Nxt@Jc|3(t=Bzsb4ini{>{8r(?j{MvoT|_K}&3ElD{KDcJOF!!F8G~ z-Z?X#ktNDRv;?DT5Y?ifqz8r81WreEqD(6iS+??{>no85e_ea?hrlDXC!UH!Z`88% z=>pew2=&8K=l}7N&5dsYwb_A*8j5A_mBNdMt{Z{ z)_+^zb@QtYYBW)-qen6wY2z=5>SafY%ei3O5M$|)hM*Y1O09VWD|-7;MSs$2TH?Oz z6BzD1_8u4Rlk~Q5$LxebW}m}Lnp*Fi=$Sy%?EK*)3z3QI`4^WkKL8l(%5$U*U&)Dl zE!T!IQCXu`ezg#fGk2{VVar$V$Shw3vY0dxUkMce>8z|Yn1*DQ8(N{~VRI$gVP^Bv zO?wxChiVopSO$=aCU4^KIA z5}<~7XZ;C?owm#ev>{+0>C`^D;r~x;h5d~r(2m^aN*f5^6BC8l32{Z`N)*U4angB*bH<~d6Uo;-F>b(~YwJNYycfRq~8CK+)?*VfAnrO5rA zBDFNyKQ!~r*S*1#hY0-N+@FV4Oltf!RZ+Yjl;VtlujOMY8VX4)drcSsdN2xi6>*>FoJOo1rTQbBr zgLS-i|C4)*zbKT6`cYztqRP85qaeH4n~ybhkv9a2ixGgc!Tz>MtZ< zj7;Q0KIn_B8Y%Xb>!LGP!E+*-CGttP4$uw}CBbyE`PqhH?q0D!bhN3?ZeI!IRwLEN z!=c1}&yee9F#T?#V%lsN-`d6-j#*8Vu;Hf>D_2BeEw08_M7I0Zm+~^yA1DHJb8GN@ zvDlgz0a=VbGn3RWO`ux;V< zhEoz`4~(WKhu6yqkVpQOoOxT5FxKG0y7Kcgj*iVLBsv@|7rrpxINllKlc;dQ0Iebg zawxeogw3n(-95>=v&Y44MClCfA9JTB7qqi!8rcefSuw{+$#{tDVaX0<&W-$eP_~6g zgCql!slC!@+@u+yQXTN{5-)pSb;HD#U~#)^8!76chFauc)e}fvMH;0PXTkWsVx7nk z{c`-WFHT@O`49%tkNo9il6oEb#kp_N3ns?lMCHXh^IfhG9bj#)=w($xwnW0_1&99( ziH-_)t6@9^a%~=ktOydFHc00^){|B-UB}ApL;0^86IuUo*MI+_FBFQ(C_))yv*H!K zN3Z)zoGs0GFwwRNjjIXx*yu=qEVOsmy5_75SwY{#U@ZRIG_q#ifi5K@j3&<$OsVAf zK}vzqP_-4IJX)!d4|q-Hd{*XDkTsQE+LzM_j8DM6<8N~RJ)DRqmI$3|J34UAk?l&&B?!waQ2tc zcJik6F@Tjb37J?*iBN3nzrTna?80`oF!)+!9IH^OH~WtiXv`R3|05lwl`6cxk*vvp z6%2=jZ6>j=lF^Nj${TH_cH(mSoCF)cuW9Us%edc3#Bp{fLJlPSa~DiXEeR&*bv;{; zAjsaWznC@u!G%M4<{i$v+!{yMY++_3XLm2JU#;(z8yod=JW0FM4FlY+HpamBTFAE* zxMzBdn~hq%j-SH*Zxz#jD&Z2XVQ1ZK%xL?m5OiY!F{ow;tk?H6UfSd`ZKAcIQM29G z$RQF93cMF(Xa3~gMVfhU49Wb)uhY{sW<;-qRv}O24}ih1GwrumyH-6X-RNS zar|AMCoY^HB(dTwnR2m9An{e}byOYo_pHp?S=}zBxJXjEBe=W^DB)K`GZ}-UN~h8( zdF}kUgYgz%iu3H{E{j|_&Be@XPqABCRhppPU|iig>FNq?2Ntz#J(v1)2@ z=#Iv)uS`sME~o5{Tn%OBH{C;;xISX+Awmw`NC*O3J6dPFuEN8?Elh*t*o1NHg?VN2 zLOcwJw(YxYhg169L7}I|hI{(Gi)GKz$Fdm0j~%LTy~rUHf*wififd>cg_RFVaF298 zZe^$vBWa(M*i{KJ12RBfM3--~-U;?hj|fwe4(eD|nV!B91Ofms2rge^%>i<2hqVxU z966ojijnbK*#6nPFx0`zgbn|BBJ2Rrh@0nDquowPC<_}k79(Nga5Nl>Z=jk}j*wJD z7Z*lW94Iq}%rwC$prZ=vWwat2GHlivvaA`!Sy1Ci``bUPEkeF>n7u>gW0Osdi!;Oy zPI}AyhN;2$Wi_b70OFW*t76nj0`CYblhjk6SFjea+bJ4oOdm{nOFM4IOrB2SVulu* zK^H0$(xo6!M$@F?uMK+buZfRXgXJA&AUZWrG<$+2=NBfXO<@D4F!UIzN{L#-waC&q zYC|75{E80)rytfCEuY%jYkB5yLuBqQUmtcO_T;DtazxUlG8UC2!xskkY&Z77 z6MCm#bE0?IFWvW4>u%l(ea`8i)^Uz1WR1b(ien=H1_KA+v*F2+5%FBttOHH6w0mL; zi}-@*wp_U+&7w~;R2x)Bb>8IBZI`F4UGTf9ew^j-fY8b=<7 z&bZ3DT8L)r6kr`SVz=|fRR z-l6gF-e5~NYQn4VuBbJX>k%%q>rMm^o;Urz=HxsS= zR~PV!s%jKt$2lGUVZqdWlN@Ayeb-4Y#k5(j#K9!$#NCiS8z-K1_{K+-ceVh6FT;@n z%Y;fjYuSarS_QWx5;Qa=YVF5p%)3bOhM`@k+M-r_O-q$X9BE(dQDuS)Mxm z7(Ee#bEA%enj0E1)MA@bcqKx@L@q;?fP+1rmJY`AgGw0r(Wwp7N|T7ZK{o6FJElC% zl8tk4G{_m-wz$55?#;Oc1!yRS7dk-nTLfwVDxXOE7nW59Q$}BVsyyvtut^kFE3z$g zZm3LI`<@{5cs7*bMSc|?JayeomZ7$mT5qJtz!?PvOMEJg5&xLKo|Q)x9qk3DY`uh7 z>H!VT(@GQcj(Wkp5l}gZD{x(ugNXRwxNrIQE#XT#2him)u5(WGV$SDZ(+NzzCO7wj zW9MU0eHJ#o$sHM-Vy3Io|1w5VM6q1Z+HEf!d)y;FW{k?yPH^d8;2Ssw@&DlNy zJ)Z4Jg*o=R3!c^%4z@AAm%_W4_17=9!;cq8kq*7uiHi zCF>Ol(BTp@rQ`==BO!QPCwx&upn=2z2^MZBcC%P$ZG5qZM|yf;qGfAR!03{y<#xL= zk}O4%;+m|lEXeXQ7b*uEt*^?xSBJI2%M{ay;FD~7OjWlndma3^kL??t-v-mOr!@iT zsU4xPY7-OAS#`H;>I@8uBB9#E>yK>MWOB0SE3BS0@04r51YF%JrJP(c?9m%^%0^7R zkse2}#~ul!+Mia4ST*i~GRwo~D5DNwYbGQ}u6whQ=lB_57{OerC2|HJMT^+fzH$DPQFKnpStZ)FVb7*DJ8aw$2W~eV zeDA1cH6|WSQBsFNX=o3LhXAbkwA8n_l;R{xCSwX&SVoE0xNwbxyp1cYimxpMUt;e> z;*Dvrl%4RNR2rUh31|EO`~XDSXY_t^+%I>1@epd!C#zhKsA?x=u78WUrDi^U!;1OF^)Ajz91^~GTy4H16#IfETn*hI+g3}r*G7fqG)S51m&y^;$ zs0te&7n4#4=o^GG#nInfqLcJV^s63(b#9c^W4|PI;#bwnDI4O+lztNCE!{&zUxJequSdN7l#5_F|1_yfh2ozBU#b8k|m}!%b?l{a!GZ@bxDT`zK z8milfEfls_qA5>5iK9SJ$k(4j+Jz+lAgp5^Z9BzNfVo0l*damQ_CP6@M?&kvxLd8c z|7Sn|iSL5BYxZY_Z?(DJ4mzQBB2Kgt}$UyS8<@d*Ip!qqc zpv{k1Rb@g;sS${_`8&l*4dNHh8`9(+`nXy4zneZb3XNsNrerws@9K=}HjAUe4@&`x zjb;TTb+m9@jWXg-jdznXQ>3YfTU(Onn zHbH=~=e%{oY?($R5hZsTWJN-?@lQ|qeqC*C-i^y@_%I@!F|uqLU*IxbI16A4qj>?z z5lY|Q6*rV73YvXVzTRGNev1r63I&*do*PDZx^q0W7L(T+N8y?$k)7R6ak|73kwQ4P zPsP)zfGg_uktiP*>h=u>C?*HwrXuOXx$o3_OYN${w_^ITm=o8kHAa08QD3*RFBlW> zHBl{lL5xb=Fj|@|Ih%^dy$l&XqCgRem1t7vUJNY=cg=M*aZuz|0UMDX0i;e7q;{K} z=tq{!{aN{4-!v&^VvK+N<7!I#<*f~Uq|j*s)q((uG{A-qNZcCF}V6L-7K@=VyGP5M9yPpqdq?h za``D9-qvL(i(J1hztk`)@sG)M#6bmSh0>~(m6;~5rNr>bZwQRPAm&hy$}e||oAz|2 z7t5!@byZUX%&6G1E%obB+{AqpN{}5WM`aUyB+ZGioSnjSnOlGr)&AsYU-@jj6dTgnUKfWarqbL7QHs-~bzqyTzxV|7`9N;M1kQ<{U6M_m z;8t>$_I>hBJd|VO_4@5hZY7R|3X_^7YNZ2{T*Ma|_9^hnFii1?E8V4Y9J=TYkOA9R z)Z5vM|FY`fBpS#2L`9Elt^EB6vDzb=J3-$iSBbC|NDC&t*?O>TZ5a?ZGe zJv7Wd{q-yK7;D1vF{x!yw%U+F^J9vZ#umRl-M<^1Uj$4P1My(k2X8-f&_&1`y}X z24SMWh7R?VauZQ04=owCL5GIO`d~EJAlX!^h1Buwvttm8qsUJ=(BZ*qhvJ!7a0mJN z)8@t~;Bwu!y$_q6v`FtrIx0g3E^IslDrUZop&?hVHFbQRN3>}g1{?csv@K`FbZV`X z!H$MSR5Ij3HO8ahZ!>|Q$oOad%Ub-3%^ARID+`Esw%+iGc+_h`xt*K;0Au@bvKl{@ zLa5>~>>z?0Af(}O^F0x3HkE0$oifZV)w1T@_b~cd>l-_-rI4L$VTMi z5)55Qy>Li_OGj{Ggbp%qBJ@fSku>{W@;sJzqr?_CHHO9xc2=2YYnTV3ogumtqAFanQq+#zBL|M!2h>Ry+6 zqVz^b{oSh!0A%8{;vV$i>kJ@0mN~?)b8q#oVS{5Eav}M1r8{K~RjZ}AK=cHnu_^QBOJ8^nY)w_fEA zKG#IEEbXZQfM#3Z>&)N44*P%&JIiDdod6Y1=AmS*H$hbxpQ#7dM%9ewhoVJ!AWoCU$QT0Kkb z=rr>!AYUWS?j)n|VNP!G0y|~B1Fz(`+cQpudg-FYAwO*(g<6J_(MV#LW#qQEdE(r~+ouj)NT?9`7@$A@=fhrJ}miP0#0 z`sFZ+Ebk-@Ic;9*4VZ7`;f-lA)`3(muFn)%bP{O=m(e}^?1@uLUvJ#g-+m@FN_<`e zad!3hJW^BoV6vZb5>NHc&$V>)J#HtJ2|>j9UFLMHzv+*L-!iHa!e5~LM?`6Z`Kw>^ z8vPcLKnv-u&|O5`R*(&!<9K3A%Ic!4j)7xD&oZS;t>Ya@1!*-WQrp3^UW+vYBP}bX z8Jsi(*AqKlMaLE`EpA@g2>IzSo+Yd`dI}XGEhVB<2XiImYZW;XD-xe7vs}ak%V029 z_^VsA=L-Wu@eEI*1Y$#r_WjZ5d;p_yOEL2iSY-Lzfj)$<5!Mn9iEU{L*Yd9lM@vV=7*-8T>gtL5!lb96#hLu|3FmNj}!GpW*LS#$*mBNIYua*Q|E>S3a=JA;J1lJ7af zbF}Ih;i?DXfvv-Bm^P5DUa}6Eq6rd!loYeKgG&ucD0#HSY`m5wCKXVTPD!#}kw#~d z4r1m0B({eqX#L`SiW@^4@i>=X3W^D)u6Cr_4oZP%PlVj7g>XjA)Im=z%Qp&<5A%kw z2V@8m{71kE#+`0Vr&#u{&@+7KeKMY4LxE;q?(m`q0eY(0|U#%r)3N5-_r{-Qpv ziJm;2x@TmmqF5Fo1tCI;^~tcUZOZhjjVM2^<1Gsk)84D$Xy<)w>pz>B8kJn(pPqMe zDZ=Fsj@YhFQh3g!N0{7`gK_z+Z0B#-;dca`GDCU z;siA1Fkk3UnB54-b_p}PevFxVhqB0qpV+V+^^I^%v}}%x&G6wunWb2p}eeAvQo5o%Yz%0WE(6Wa0ugtP@-wF)9zgWhSvs1>YEK zvK?#2U*_!kr*~_H)0bjcepHaKt9Z1DdGx((2ncO|2#3f^dfl4T9#6~LiW>0h8G0en zp_nAQW*S#9_&bd>^=Ov2vHRjP_k^+KD@BoTA8BOTB=={?0;N;raN3KJt7~$2{lr1c z3vZtmHEJ?v2*d^`A+DL!snpAJgF#@@So{iWCC>xbBd9gBWRMn$Hc&2mCm{%E@*^$pU+fLXk}1`@ zJ5*zO8o8yt8WdKwI^Kg=HcwS5Y$`1$9@vPh3Ib`C<`5?qKDdja(cy}dMMCpF&|J2x z47uV}0H9a_XKldN(Qt30a$S;?WqC*l0H*bb$o&A^BBNQu$Dw$*C0o0UgXvziTak}7{@PI(Fj-6v;GQia#HNF5eG` z>hS7c#5HOip~2uj&#?E`Y)lZV2izj_eJ)V|@ln~Lkz~9q9yCZb;e{GIj(^H)#^5Dp zgzTABk2W*2ckLfs>m&AOq1Np^r*g-X5dJr+Tjg`R6sOVp=X?BGvth}gn`7b$P0yA!weWnC~1tiSy; zmaV;U4&^CQCQ2Kyb+Q|%@r6Hu-IRC_RPPSBY*RuhdBr?AG@q0V5EbPNGfiO)N09)TRoPb(wrq;@`! zYBAJttx7v0n#vlL24zvz=2D2#-Ug>Mr8Y3A6;EITL-KcHqBEh2uvD39!m4o$)KneD zHnMdZRoCq~DlezC1^}-wB$OAQU4?qmcT(EUMOpf5c?Hr4>Zgb{2iY(D;VA2&`m87t zG^#Ie;G~o=!z?!gCJCSr5;n)8@&Q|*?dc1nqPB)BRHsPLO5Z;|RZSNV@(eoiqw@9i zULC{`hbdKSgjud=GgO_~AVl}LUF&hR}U+IT|EPOxp$k;Q0!ao%xHH zhiI7y@I1DaH-hkI`(ZI4r>Yd)q>FNMga%xa#ds4Uu^m>z)v-`pZtfM zNL^V>>5IcU&Hbj1iJGDAA94+7WNk zB>n(oe@Db#1t)T-!?~8#f$D`1k*{!zTY{DfOg6~*{x@ja7ey9ucnywBgaxOLx77KZ z63GJ=IKCO#D{CjHb#!Kw$&+b*v*yilY%5$c^{q&5>=0ji?-UbruGiik0l zQfA!A!pJOo0iGVN5Qk)qfGKlZH2TIQev*KJmeqQ*L|@J5swd@aKO=I)IMmX-EZUN8 zFdFKFT$tU<-;C<%1=ib~mCc6bpYBYfXK|}Q-cK?Q{XP23DX^lI170rBdB^7< zVQkKqqVZ+neUgHk`a#D;&WGDcw*DCO%Y^N{?WzgD!a6{vah zSBLML_4-F>z3Ik5JF{srJ=IHtHayl%#C0AGQlk{L^%0d;pgc5gIRjh3D&ZYK0wC)| z=`rA_IKUs%@B46p)bQyC9w5&abt=MOh>`Ed^Z(8Cpc6^7UUi~JQEiLmqAB88|DXw9 z`Bkb6{!E%LW2xpCq!RxP>HhEjozJky6#GANB$3Uc)}%%{65IW3khz=fggGC5%6yQ< z)K~5pKaD{#qVUGS`8)J?t7&(S;Zkr3rkeiu=U--Chy~vKx0~nDM?#qf`O5wFe{-!J zaDa{+PjoO@+YV_*<^QKzkIS7RI26090d2|XKJ$`&4ScbxM3=R=sk(np$xJQv%QcBOuECdGZ%fWpTCO!ub1Jp zv!XWuZ%Q+U$K4^}_z(@%a07VuLO)Vn7`-94WIE{x|05)09rP+YAKKi|TqRn@RgGO$ zd}djh(@2~Q9@JAX^hv5~Hi6oc9AUK577W+L@;KC7dB))i2kK;#k+}Fw*pwa~PvEBZ zvTK~qk}rF192uUPRBPOO7Uow}p?g+rvk{3B3(KUbHtW-4L!1*-DLozo>ii+T!8Ms*jbkce!ppf(s+|3DPRzc^9H_8s8+02)D=s4374ZiopZ| zmSFR#r_a=yjchG3+m!035Ccd8TdEkoU;f4$yNM~+yQ02$A;|ui*`%sS&6mLJC&22% z8Yg&&3sYU?iy?5NYPcWZIr+nl~WB+OsaqnP-nH#;>D5@vy|#8P{8OgOUZ!J``0 zwN-SzZ>mC)?9fcV{uy$|F;weQ!660*;c-y`PH@uo1_~?0acBM_?%i8C>h?yx4|bK| z4n=85QNdK6BeR7h$KYGAxuGc9u@T{%a!Z`647qb5+mYI_sBLy$v&9OQ0~tu6$ubou zY=kIR4l&t~C)0wtuCc0{0^f5qb!qtKZDMTK%UAtIt%TX^ha@h>Z2;;fdCzQ|Co!Nl|0>+KWll|U7cLi zG+LamK5xwZjIJ(b^r422cNuSfu#iHiyNF)GX+3*#yGDiaIfe=_XLic<9DV`Vybg|4 zIUYEK$bNPPK2FR^!B@A(7qCNrbH|Fm8u9TiJ!(dpCXyT#)1`G21M&;YTpdzSvO;T5Ha<_KR!5V&pm)N)nXA%0$~ zTV8GEr9V@oE6WG4&4rOEM|;qMjh-k-nfWyxaTB-J@^OA7lHt8JL#mC=9_<(^U+Y%oZ{sIkf*kU1Gwl(4%hi}a`}>smJ9MfFY-b{v3ylO zPZ3BTcRdWLdI!+?OURE`ON^%BVTowkfTIz*aZ`!s;k1ssxfT`5GtD2v-IQnbZhhXm zO4tKap-tm%_8mNdyw} z1mPkQJ6;rW~E7=2=gE*g6)zhe?}0|l2~J-YUon9*9$mexac;Y zB8?qJdY8RTzXzow(2cyp+L7Fir}lGkB_yDITsrCK`lebe!HUK*VV3UkFa3>POfasy zDAQx)npx=MF%cEj#(+s!Jv?~X$q!~l3dX`~$>3*v^Zkt(%#^(y5CeMv z>x|Z#!GJ%d12!obkPb(D$YvQ~a|Oy27JCs8$Sx?k?(lOBg<)BD@B?S>^)~tL|6=;M zer3;b5qM+Aw0as6uF6w)OG(RDhuLL99Qd9hXyC`IBeD1A9>3X#8RgQd*`+=bcmRC$ zfaqW{L_Q@(^?Ce7g`)>J62z`%c&MXr=LoiQ&E+$vGl`C8lR%JZyuEP9QqvUbHCJiB zT6Ps(0os;OGL4$ZvmnbhmP8qEqj0MUw^kg`q-hgdQ8ptmw6CUrdq{goWlzcWe8qK3 ztv8sHY_*PS=o@&M0^9(c_L2pH@Ssl2s9u#1i zK9a>TET9zBo%XCoBrjHC5h=&C7HnHCle+1P z8goD%!=pnmvzEiKzLOs#AjxkW_LVgJalFWlVq@Y5^I8J;G~PZb>;A@gIA8X>2*AD3 zLRF)FBv$wO_4biKYl38T^(9n-I*pzOXJ>UQJ=X;3cW*+111## zxp8R%$#O{7OS@O%Cl4$R7d+Ji@>Q#>kHN5sy75=Nwr*|p!bRD=is$206W0{!(dSYY zygk(|I8q^3Tn2?{;d+RwUjQ>#e-wUxwDqYal$Ie)Z6Yp@eymudF{WJ2fyxTI z{NO{hT;>Q-S_S?h+sH6wK7N_BQeT9Z0BO!%H11+oU)w9iuxcwOe>?3RUtyY_c$C7S zkUKcaV5$Ho$|wl<=_x{P2-Nk$Y9ZIDNLAt;P{jBHAn#nmDLsbkSZhi1v!}p-5vxpN zG)Lf8mGPlL``Xup@>=9(ji6xuf^{v$IVD>BK?_JL$0?#eH&cg-jSHp(sgtFQS#8H7 ziGG*v`&AVR9L48$jDR#8Se>5?5_H$=N>mTi(BHS)OESd8C~0B|kaOF`G7vazPr5fB zq1wkib4*7Jy~BrAt~0bXqhy*YH`{&e)~|$X=u~K{q*uzoDZ=C)e~@|$juGjyD7yXW zEZS9;R+6S5B!x-?z#}Keha?lNzhm243vD$wi6D|`)jKjHL|duC0_b^WeC1U75QhfH zfNiy#mhXKNps6|<0A-kVA7O9J+5)5<&_`H6GHqbwFH&vHV+!*bRMr%&?=bYdN-PTU z!pSiNE0~`QdGcVZ4)U_-3mV2%56UhlN><}6d(XzV*?=F@d2}#zP5LTFvV}$9Md@7X zXfnB5Me*>w6!3UvE;XjC+x+;of*yX?TyJc06*XZw2*b)EO!0XWnn*}8R5efP`_UNN zY<%3@ELDD^;US0-56_q6F5;h@n)Tgj!zvh&dEs&ZUDQ9`a|1fZ4@I4?LYADLkTC1J=%J0XF$Y4_Q!3ukPl$0z!-~qmekQy@pA%jrpYy?_NKOJz7#tyFZ*?5- zoMXC$p0)h*f*Wt>D`p3!nn4U$pgEh0nj~0ZioAxK8*XDuf22zFHM?R7_f@wvYyDD* zvzp3N8B*AqLdTRW2L?1dHNS{P>KpEM4M_T~Sop>|dIw;(T9Pbjx}L*Qx8q<~@;r$4 z@>qroDM34^-p+!J9;Kc}I61@95mPo*iGhb2ZxHa|(9n}iNx|}xV75qfwcd{Y8IWT+ z9P5w>BK#+WkXG`uSJzs z@wDS`mJZCF4N0}=u!@jv7E37gcsY_~z)m2|f@HJwT57k}E<93A{LSWq1*u-xbZ(r! zA-o02KVGdm>7Yb!O&^bT=u6%rwfpp%LfLF0>0MEOIY=Jp)S}TPPY7(ll zhFvF*MA?x;qUipTi~|FqN_#GEao*JWz0Ms9sq-Jn+60xh)7%>#H=^{=dCLRV^*H0Nrl-CH4~2 zDD{iK+>ZVUbB#ONJ^LpuzHj?kK)O|(|a$O0MW&A*+5yTb~H zR~3wcQKx?;w|_lL8#?(aAsI$?rD~8vlU5E`W{8v=&r`OEXLNX-@GOz5OUMq3c^^vq z51OfwNTAFTxB9ACZiz+E&%^FS>;!-qU8xvFEVIoZ7yXEI_1FzV6loDpNqd=Jy zTcCsD6uwO322bmB_3UeU(4 z0~Z$=rQj2(>^ybRlcVMKACUT9(tGL=(Eg&fqBt8*i)39{w9N(`6nL=n3*gFP78XEx zA?T+qV)b4-$qt_Hpoo%@2eHe3J*`-`R~>aO|I7w@D3}lZ@}`T$LqS9qGrb=O3h(hx zo}yzI5fssxMrcv$%cDHCj%Ba+--(j_C{wqNE_J8+#Uqt znQ>o^dkT-6(N&D#;r47-^RU8%nPCOJVgIL@1l98e^sCy6Wwuu_wgyux|7ZCLP#a^% zcm(|mXimN8(~Y2iF-F&S`v=H|7-{VyzgS1CZy?@Vhe`r}0d~dGf-Hs}dK|YCb|+zc z?1;uo7%Z$oG*uu3Ng73iDR>+2yDl2Ws4dl%$7F~>QpMidWT;g!cC29CQKyIV!Wm<# z8rf*gsbtTRGe^=JUSUXzTRRIU5~&5yg3W*nSUK?S1Ry}cSALX5f)^ooDACI{+#Em; ze^-JMv{-rxFJT*37dnEkMaKqF=eNsfYocMW8&ZC+jpSX;Wr&|sWJw{C4SLiMyGVA_ zT}DcO1#bqK*hE>lWXIyseDCQ?BKV!5^LW!;qi}s-2owWn9Abm2IDUU&`OhR~-y6kk z-=G0>&eFzPv0+-`Hn1e_EClt*(zn9lljmvc-w84Hm3C!;o*lWrQ#XybvD*UG=Kq;L za`Fswf5*c*v>^sjF9?-rY@LiXcQn9CXRG?iqlk-W}9|;d$ z&t^{*QH=kc-~#KbztX?fcVBIhO)!_QOP{Hs5}Ka_ zr!lsQQJTM<{AW3)4?C=bF4EY}(^(HBp2{P!?HOt5nXYzLw_DEDAXU~knc`n==DtaA z2VnD6rt7J74t|j?&0gS-`UrJetgXip`;afQGm)%dJuL&5{$hct<8{qZzRt@uug?<+ z39QMxToF91f4X9-w1cGwQo#%N-hTMcWV61r-_*8eHgxjlj?Y7b;Wg_&3hFZ(tArlg zy{-q2`t_T726uhF^RB<7BoJ5aq&=F7{Aanps#u_(z%+bOmdWmnu#l5`sPxY>aJlR% zvbsS!DaDA1jU$Xd3qKr6@FaZ{XJ|`ZmO+%4;>^QY_h<3x+rx(UET|_#R2lOn8L;mr z1k3-dYK0&RxNL}9xlk_4AzRz^k5i)1m6z0B-Ty@|+;o_D5b4?Z`E5R5Igi8XLiQ7! zq1$36{EGU?7a$(Z^{ftYJU?MxYmIpN1z8W*MZfwt@Z^$O+6pee*_#ptz-=c;Hhb@f zs*>yY5j&|k*!m5&lP~d{8&%bxNyJqRt}M5(=N}dS6gKkB{7Sf(!2MWpVYKCC8D_~O z4Zp
  • `z|;_}Vyc#C20xT@1&14lL5(I|d@*cmkWfn7WlfZKXXh4<~Gp4Iandq4Un z*7G|?;Hzc1hVh<|U>!Hz7^esAmx|GPee}n3at?qy-Q0(4pfm7QSayKvmC_+9q2QR` zV)oleUQ_B6dA)vLI_m4LKVh`1z_ML=Ig`5EPtWUcLKv*iUd;c9x(yyaTAxrrB!!?# zACzSjJ`X3jAVcE2)vvsc;5$;O3@TzI)P7}^Dk~F#O`c*BuQrp8`5^(RYEGcV;li>l zl|HqE^H$-Q96?h|qSUbv*rS>vq0OqQ=w7j|BESKMs5#!}@;q*HP2LW#?z>dx6KU}8 zmXyWG=6aY?YYU6kd>7dO?yF!+=jXYeQ(|X(UpBslhzBgARLe6@edgM(J)B zY}8fYKa@ib)h+oBV9$3P|9mdbWwIDv4S7i`#?%C6I7Y;nqzy0W{`;cmz1&Glx|1^J z&v-_Lgm@(O@;@vk7ToAG?Ork;{xCmH9`70(e?PJfh4-ZAgdsalaTyIeUmqmcahpnv zqCQ#bws=PDV&2^D?=8moH+ZwS^U3oU#hukTJ+;=gV#DKwWD{6`MQ60MURyk{U2PBQ z=h%=~RGbv-v^Catps`B4gqRV@oM3H;E_R*Uo=it(cp|8a4zHqCX#K+Y8uppu@nA3+ zxkOo`z7qqpbDhA9tU`nCy}od%u+YQ>ZaWVA#BpTVdw4&Ix4o{+LO#ZLz%UAz8^Pr(yF+@<&nIs-NleU+uJizdcDu@oqsn>um55*>eobqK8sG_VIH8$BOnVN^ye4Abl zHwj06cg=GQ6ri_?N3qnQzz=1^$I|L#UO?h;R|c98qIa)%CK9Hs57o&pvmc*VwRCB~v~>U`F{?7a-hXSucP2M^j?0S3LDFrhAftKeAYTyT~^~x&^a{WU81V@!&v`@hKl5!^(I{Xq-c8 zVmRBda7t{71PN|vMC#BEee^6XB9{qe%Aknh^>nvB@)PW*admMp+ef&ZrA=M_81pLY z+EnKl;Jsuc&;ecBoYijq1IH-xd^7gdHR?Pw5nrl$oPKI0t!sF&L@NMV1&?oRnnG}KB!&H zx@F>Q;G#noF#Q>0>I6g%jLK$Fe5s??5;mqIIkR$DMfk4XrUI z+OW8Db=%i>OT4A=!;%)Jd#-ZDEQp7K|s-X!6jSzwyN~dN6Cd+6r0Z4@8+aEy9!^T}%xuI@lRgGt#KLT=x zouY|8fiOl=@f;72tWWvetP)D597;Ku8O`#BfZMenESjN$5})zPSbf?v=Ra5MGeiTo zf4X5IA%+;lL4td~Fo4m*TrCa#-B z`PLi^;a8FSPA}4qUicFm;VsDtFZ{$d^mp{Q9iQb3yuy79___@e3S#ng#U$e^AsnEA z&&gFRUzWh6@U%kLT@(~P3Z@Co#A}ze;X%kn7M?YNGksa!k4ie8jdWKf@MN65M^`M% ztzeN>C7JVPjET$KYw`fw9n&`xcGR&0DMAR#pdy4RjL#Lafcv1U@Th;1w z4VS!4N}9^=B~q8R*BK0Fz&P%v1-0Ro2F;m)0g{BIpJ;z-1KrYp>+aqnGP=(aB1Qc< zwd{Lb=C^AncVaKiCq+1bZYBlF{Zs5sn`NTL2b)~=!vlyYz{ic?A*p8!;`yfPQFY`UUEMqi%kpw8bL?vO^Y?&O(tLI5|waOP)EH;7i z#%U+4toos13~1SKCN`-J%|P8LN`98sVvDUJ2?rxom5iF`6CU8*yp>tbo%}#k*<`sx zmqZg=|26@E-190bzV0-Q+?Lg@(H3Y+nOZA`B?cO!Gxke`&K2O>-aVI9g9i)HdC2JV zI&jp&Z|&umy?4IJtP_#*bL`S*Trc0<44p;%oGrPJob{koi&eFgWU8mK=a|?LCmac8 zjsB@olCAM@cenWeh_h|ZF-5Fj;h`%Hqprr`D2U1jP44~ic_V+Lhfl#Ii9S~i&SBbW z{iLFpxM`!TH5D8Yc8O$4)j6Z`U>H5>S(u`c4q!-ata=kI$%*>`Bx%t@qY~$383)yv z{8kZG>Jv$Xj^L&(Zb)z z6n#KaVo2BcSZ|Ic%3MoiK@`HR;7@3Plv|jM6qCszZ{|9>M;eb3E#u1d!Byba`O~YS z;z(tiLfte*##Vb>DvS|q38G%m5c5^oAO|gWvBiDNi4`4wnbriIN-shUm#s2PGT*H5 z6JsyiX9+=MmZWSiKc%r|pdrjM)wX|#3>ZtScJUXYwJM~%2M^NC{RP-|w7Nap!V`4d z9LrcLfr`&M2EoZch&^l`FX4iz6}^K!i3Wep2UNueT~xXVV_M5bDRn6dnh^Av_Ja=1&>onjmtRi1o7O%1SEedeRP*T9pF#b zR&Emrpx`*U1|(LQ|Ln)_f`vWy3skfuh-P3I(A0|Iqem+mGfsxGZ8~u^7?*>J#+Apv zUi9RwdR$2(#eW)~3k!7r8nYMoscqlZ?{*;01`DQGr!dDhyjWo|d&1bJ)rf;B^+t}b zf?uNinsh58#zc3G-qw*k!omu(_3K^;W(&3u+?X&}xui;u&QZx6$R_knmW7DZuKsi` zo}LE{FS$JzPv;YM35Uiz*#xGQTPdt*f$m&hT(cYo(FBb65*SfqNL@T?S`p59*4!UX zo6WasdK)#_4-tpvI$@|>+$#? zScrUNt%lGsQ7AJ{iD0-|c^Em=wh?t3J>4SCO#?-0766nb<%uvdIo3?Nz_?|9M-yy| zI9f5({IHN#PSg<{#Z`|&RihaKCuekZ{_5Y&MVLOcE!ZaH{q(I7EG3YrY@uRcEIxHj zc3=61kXN80S#>R;HZ#3eYJ`Y+r45UR0q1n%>{gWOnWGxRbk-m43uL|VxBJp^{tQpy zVJyk?V)pX#i{7@+1XC5^QaFn5w3x+WM?#LN6)x?ZG)35&{KvyuiUCiOv5rr-giLQ` z&|m_fG(H71$53>*;GwCJIf;N@2Xo2v;TgQru$HJ>Fcu_J(>0r;DKJD5LvCt35Bm|; zT#A7iBzZH0+|^MR=A`+1@EukAJdioBx{)k;Wml6GlsI?Lw$%JH`Xb@t`RShmm?wLi zdf0pOlRiF2Zry!b$XRo%XTwVFIBX9|p2W#zk-KRRP*PCCP?8kV8RC|2KJr^n$bEv> z*u1FaPsp-y(Vi>bMTDQgiC<2`>eamf)%!tiT*JyO7ThH0bJGC$@Lq$YqGey+&~qU@ zC4XaaV-YYC`ybCe_OIuj+E%Kf+)}IZx^=@V+kWfYMXDnGzpbcEdVtH^=hNgR3lwSF z`~QAWk^W8kyHX{B2Q~udF97y^_LbPz{DR1$@3)10JumjDT}u21O<66_9#Sx97CL-! zr^~3cYo5&KWnlG8tn!spHg3ZD?d`ttjjxbm%YK=tBu}BfFaEAK+U(i+TXyMV#vc~> zDwaO|i_hKgZv>V@ju3W1LzQ5->>`k=dh{~YOsh%JZWPtT`t+Lm`tGl>u&r20q~%V+ zwu)miqaM+m;%>MaJw{r+D9(EKxZpq%o7G%T5VyKD?IZ~w=i?~X^-rX`!;zLwYpggY zRF8O(nH`TreU42QM+=xNEuK;rb~uZ}V@>I2`t*=D#@f-njhak6 zvm7>w@h!sGa5WY#9+5E zVw%z}?1YuY1tIEFT;I08FIH2MEUDxXB74F1Ni);3n2;66 zo|P4E%R&!K9&g+AYG(G6%+DP{e(cC0iH_l}nAF0xMntSmpX#xBHqK~?Xx-${i-|sz zGCq4&o@Ve*UrG;6NEs|9b`Q2@zxOGK!nL@y%#`A3mIhPQolGQU}pRKv$&&I=_- zAVFjSr}bWGCndzKf~2vN1Ru16CSs?MzRH|vyO!DMoqiO;;DdogH!v%pU~;j5@$g0= zJhLg1uuN(d!cNZkjX>|chPdJ?iZxmty!403d&JZZqvpety!`83Vt5dMcDtg!t^CmU z=k?!yUVnZnGYE0?t;%g=M-`bUuvKfWG}NxGUe-Be@y_^vVFv|_-sWqRyuKJVP-(CliygiHG5vowOMpTrQqVUd^`GEBepvq@#YIU9`kTf7 zS#hOI${b9zJ??84v;O}Z8r>!@cs2}uJ|;b4 zo#=hE`l9l3_r2g7OY?K$Qri}xdbQzCQ$B>BD1IOL&dG0%pZlWqkpXFyZ7x=kD_)Qb zdtC#bl9h6d|3a}{aA z9?zc4;ZUCGj{grE|NM>c7r|#^=>jFe)stB>P98Ti3`GzJlYQN?_00F zDww+7)74bQcXIK0jtCe%U(o$SEbymip{K7MpshTb3=7g|in+iFdghbsSn+SG>n{N2 z$-4t(Sq)`Nt&mUXQU89}u_7;9%Q-J3GKku23>DDTrKwP!zI}Z{uL%_f8^YuQAHg+> zr6R!4zi-g0n#&#Wd9=fH3^iIoosUHS!|~sxE9-Tc0X(|MCoC`tj{1yZ%!ce=0D+cR zGx7azgdqa0>J^ka#XBX|Gcsu_Crf{rkzW9cU92t>4w=Pr3tLgwFk{M0lC$^`cIKXgl!qihBfi=-$dtl*OQ)_@a}ZjkGjpo zZoeQL7GsSJ)W^F1|8zHtFA8!D-u~4R7=3KBim)Ws{}~@PJCERmnSvg5_bMv2knX^v z8`Y+ZGVqaDDA{pD9G^+eawz`(?QBKu*e17Mxheek3*MvAO6Nscu8LSQ_#Tg< z@&+1{1GD^*@QPI4J zQk>YM%kX=nFVAjN`Fx{ZdVF7&S(_8<{FFd|jW6~LrLT7g02wx{A`tGDyIn3Ce zFz?shb6J628;%M(FAlTQQ_px%fw$r>($K^O_mw>3k*;5L$dv`fJjIqfGMA71>@mJ% z@RWyjNjXO1K`rlI;xSWJ5muvFXk!RJjUhh%qrbhiK1E#H0?(*?ednY(bLM!S4Qq6! zepXOSRcv;;^R>%({DzmTLY zt{J1wHvq5MW5)Stj7_W>Oj2A}3oZB!-z1g|tzg8mS*n;T4pgL&ZPjg}eihaK%OHH- zn52I4!4dD9g}%6dh!QMN&fs zVf6fysXBtR(OV)IbvZ<6KIFMCC0%*7pBU9h!e7=cRa1q6w^MZ`S^a5jUmD>EqBLS? zDLQn{?isN|;ABdk_!5E_3mOUgUs=$*cv#B|SczQH&5LC}$P2>Molns=s!rth6{oAxCG!q?ml#?A@~q@V*OhM@&p;u)aSH+KCq?Cq<9+1I zh#mTj>?;x=WYm(Hk5`vvJR~>rni>pSRYVZ&?)Q1dh6qsAjr2%4q)7`CD=>a~<9^&N zGCClUIHa5q=x2;!f?T78Hjn>~QOt|^BetxKplI?7{-F)(^1xlJ+Wf-A5e^RL`3;**blM!Q~vM+9F{1b0nq>71j3hmVQIUnO$ko7q?-KqRw;^Qw)jiV^ouH|iDTvox`^Sl7IpjV!0qZrz5 z?{=pzi&R8tz=_4}X=-+i^xr#Tr9I2b3sq^sD1F{s-SzR6WvE1sAuJzF(t1g$`WPGZ zExHEmN^8=g1?jF8siARF4n=7}ymhv6M|+)tShI}+TB5cvhK}{7Yxq@|Dp6 zDq!UtPuO$Il9n%N+0}g~cPgJf9w%Q$~Y>UPm#soJn7&e@WHm zP}dRVezjhZ2mX0lO{-3P_b9KqDB<#9Iwg4Fd9==rM?F=gH$Z>+rToHPG4n06MvdFO zgtT$o@EerEDh1dPj(z|&Xi z;itaSi5=vt)jNs`d6+UJO=eanrH3dX-%}v`7!gVED3eKVXJPwKm;B-TAC&kcB%`&C(wR|zhdBCAlB>*lFui zKK)knQwNDs(!X*`SM;%$x&edVw4Zj->oM`rHW89bnH3qg0>4SEg##F8zTy$;mokY@ zGFHSUd`1r6L1`n3s4aN0xiM~h8P_H0A`AEfpPNwzb6N=NWVpd}u)$@d@^JhnXCI4Z z4B>RFOT731N8Ozig2G@ckVQ47MBW>GOCXj<#f}6jS%8s3Slqfd$DCYlQ9`k-J1;+|c(LKsqo(sBgB} z6XnbT@ZALrGTzHbiQ6`kM-chSZ`-` z;fRbsNiG}As-F!~CSz~}N(`f#PM`i-`2yV+OZ`RT{~+!?pqg5{uF=pFnn~y&7((y8 zh@b=#Na$U<^bP`2R8$}Y3{6AtNEZ;KcTl=?=}o$Hu!0C!&Y$z1`j$KX?;G#9_hw{_ z6v*CrcAm1Hx#pS^t|B!(%iWUSpn&k!JnskoQ>YMsRSct0U`LRW&w@lZaWN^!st^2tjV+_H-t9}XQW@z+MGV*!Z52h)#abu!hAhtD$#qy^$(5yG)&s%tiFCU3 zXEMyMB~cE70%gqZJp$Nwv!y0G{^8z5(oD(OM`W<5I?LjIM57b zDp{e;dJ^UO6pB8C(TyF?`h4MV@{Lx>&F(>uzb->ZwH>~XbC?H{07Om{jBhd99V_I; zE~C+@2KXPurMxuU;DCH$C5$ag@1+@Fst3%~z{{T-fZ11h?EPkPX~KtqY*y2fdZO8a zOjgV?3nTju5kkI|Hhid*Csto{m@h3afpI}LWw6%hWmdovZ|e?``z85%`}*|AVh!_)*;@yVKvlexl>;MT`kxNmLhkmNU&m+Q}-D zyW05iOl_dnLa8$Fx=v&Dg-jD3D-b7|a6~LoPuu0flr($v6&*1i+F$ z1Y8mB>@i7N6;nToRS6K}uPcfPZ4b*yPmA{&SC(Yuz@T0B1u7)RNv_QOTevI_gV zp2QS?5I^F}B~T}b&k*I>e6az~v{Sp#l_EYI$}KPIK@X86 zhSTzs?hN8O84C*vDju3XsBL}`F6mwf@8LHJFg3%Z&?R|l`P70KOSiPz`n>10hXsgD zqYV?hGlPcQcn__U`pN{ixmeXcV}r=q1D)(aQd{q`94YUzS9Od;%L6qnRBi3xU0%Od zdgA#h1)3(aWDLySZ>9HTQ1;3N)ZeS7NFOW8g!*SOF0r9mt+XKa-H&hMTDz0+`pGZy z!5rlvzGVnrrUjpJjUiE$-+bVsNQ&a&7N1{34Evc;*z>40{CL!?`|;$IZrae2U6%-B zblrpipFMMA@zcTE=_2_Q<30Y=64W(-u@9d#%*!}iSklugZV!WzNp**erZ*jKaMk4- z%FX8cFNcR$3z28L)M-z+AOGtX_TAP4dr=6gsB_#wEYbO`$J0|S7Il;7`W@`=S>Kz>ias8MPzPN~W22 zO`|AoI?d;qOY!b^CqSK|l0P!4NK@m1(Zw>F52cg%$U7$sG)rs^HdDJPX5iRNTL8}7 zrJpf%=DaKt5#zkBkp)U?Pr!Ctupyhuri&sB1c!uB)C;dPPu2war}KnfMZHC8VElvg zMFql1F!XPNel&#-U15x+agZ7hK+#^r8-8(Xsc;e=k;Ys|j;_SieYzu|b&pD}MeYcW z;OskTP&9=p6cybo$?NjrUkQ6VYKHYbs}nf;0E_pYrPO2qR!=?bTMAGk5X|(1k^YU< z)#(NN&M_-rLrR4(wKt=_h*7g{tAi%3W2ZSE(xn^AhEXFCWYyxgs$<|2H9W3`d~N_( zw12j%5N;zD#IVz&+Pu<&GauZfp_=EWk@{m5 zJ_dS9)Pw4+hL$Xm8BXi6MG=O;my$W~fy87j$5#%4^ZsjYNd-;rq{EWxrSe>{Y|}{) zLQ)Ns~MqE3%2o%`eE*LJy9Si?!zIvc*qV3O=X7IpF!s)6~KWm7lv|h{rc~ zyT_8~8>VWOWq#zPrwV&YuQr(!rSgCfIyKe>7*?9%GV6QUIz6O7sJj)VJ>ABapC~Uj zoI>o}8B;-1#hwBvqhi`=XbI=e?WL)uN@~IB)&S}~Vlzrjs}*F77KR9q%(_dx$EA15 z-3%(s2&sI(Y``kO#1a-)O(MxG%1VOj+e`~pu*n-V*l7L)osU7PlbSJZQ12W9v??8L z-)r+qUbqt-18U=}s%K|6zOl_}o@$K{Ep4-qpQFIuHq8-~$B{WSxM!+5j=<;L89}9# z(@)0JWvS#>hIl5w}N`&@I?U!)1ocB z_xkqw7`(Kbl>o4?m_{E_`5s*#yDD@^FB|7tpOzD#LoofhckiQ-&S4hM*izwyEEUhi zrYouOvkL~LGRAvcHl9(`22;1R(o*mo#FClC?P)5;>*JPln*6)z9ZnN{d&vpSCHn_f z7VP8P)oX$z)l8>H+K*4fd4!Kh%#KP#U+&oY3a59)<@U33!1Fw0 zGfX#MLn7dII#C2R&pNs|e6u@094*X0Uf4IygdWXpcxRO}ta0E~YQk1_{8+r9heFW3 zrC58YmoAA1#LzeQqVHbn(2=t1kjQ4EA^je5e1w*#KG1fq@$m4}xKLI!VtzQ-EnJ|S ztKk>GoBfSj59HnvwIVVF;7*OXoYB?0XLpPSords1lJup{M-pauQjgU=pB+DaFO-zI0-8siLCnE%Bfz0=& z7zh>f00+TCk^O&H>cSs5aDY?`@rrfqis-~p%(E80K zlM6amOL&am@P21_oFPoynAa7#CNVbK-Wui)rE)_ewQOQxdo?`BnwR1K$S?#((edRb z@NG!VbxG;ym_~^4HkhNs;-Y$B%}Zsz2^2lJwqZq+Z!nH|W)E++Omb0tbqcH3Be`cU zY*%_o^cu+AX={Wv*-fKEX-$C9j%1sjh4)+`T|eQ zGT*5*`rZ7^cP9|v7yO!9!Xjj#Xaly{D&B7vU^u78hf(z!fDtk`d2_pHpgO{x#^uZhbADJcYQ-M@SK*fF5+ao#&*_ao9L2Ay5PZ^lnThe)$0%6dVgH zHv0fyMjDb(lA~gci?e74Tp~uSyC`W>MF9xLelv~2*)>+|v>Zd+kam$HTUm6uaWlNYVTuevE3W^I0M^s^$R43%_@XD53NI zJu&M>w#B~W%u`gPmt-5V6Mb!8`ER;Ei5uS)l;j*`!&q;wul^wg^mA9q%M5HGPP$xp zSHuyDBE3|==<~y(_zA#-!>I3D(nWshAjS)KlA*fmKfir=@%Q_wq*okQgANDHg{p@? zzOLT?`~A}er7lDB!a9FDw;jA!{YRV`+(k{%b1Qr?w8qF?`W!7{9V(DL{KPV#uxSLW zyro4Q7yp?h(X8%+E4aj+HH+(N|Iy0cCJKSIDJ#E{O!-V*+hn~Eh5XU0 z9k6#}Vd|S>nd~IB8bof zUgPg6qLu?w-{>n0rV=EtXXoz+vCUtAIVfj60~rG_WJb2n%wv+`I6@eTmv`mLKU;7l z?oTe8V=QQy){yUAa;+!u3Ll@(vobd}N4&REhPsK_pOZa$&`Dk#_~6OyAJer59QW&2 zi;B`IqrwM0yLnrNS}kalpM)pY0dJKvF^cQ5UIxiX65^CskA9(mmI3Bkih%8ncS9 zx*rDm@$)~7rA;Mmb1JF00%4oPQ<>#cJ-2dkKQIvU+uMIS7kTvh(w6S}E@De!Fvjf% z?pDLm4uywDZmrB|%t`SC(_^yt_b&XlR6R_Z`7?Zk^7-UDEA53Fj|I7qvtqB`4lAr<0`Gh&x}F&9I7(u~ zh%ITU>o=yYSk#!3HP32@%F%AXF?P3EAvDe4IOKkrlH8ZF0jy5q(2-#$?x9^A^Owdw zl+$+l#&LD_N>%X}rSdq^i$29wUXm6{re)hGyf}a3QKl{feQZQOX~K(!`$OW-nDYg5 zbvN{PmP%lT(t2LV{i`4Rb98eY5IwrnDg|R=CW$5!LJ3Qr9;RD#rwtk#pDr7)UcLT; zj&wJVMlwn@f!fJk_)UxX$;JuVyZ)(3Vwi829H0e(?T>#=5Vw@>qxJR+YJSpZcI9Jo zII^We<%xJ;-?V)b?Rm=8#jmi(lT5TtpuMm;gqZQ*>!`0+ss5pW*xHj{pF=L6@mjxK zltx`bBcQ!!Ia^9c*^~aRtsQ|i_xQ#eH!Iyl=3JlUFXG$Jc-@U-` zSGqYC4mDb(_uxFZdW^5GPBSY$G4j+RBOOtag{r-wyn3F`l*wAY`u6K|*3z|frrE0@ zyXzw7`Q|^*z$RbHGp3>q&U`Ccs$cFzJ~zW}g>#3JIa!I#_WNF9Cw zEJ4j^n!AEHBBzdv*&00WO6Y<4?Y#Ef{2hun{dt+y?;es zoRmBWYVCRAAR_j_j`R*HX67Q?)?g)hy3%om;l|Zt$@vQoB~N|82cR2*rSR-L+vu}M zw|uUj`QL*`9uL~>H?&G(PHHb?6EQVTKZxUqi1Oa+qf-i3W$7PR4GrRbiUM5J2Sv(T zojW@3VPoN4PP<%JmQFAAz0DYIXHj0O^{`sODGAj7-Qzp9#> z{6EsL{`{K}Y(0WaCJUol6SX;i)u`OM0*br0H!qzS^Lz?Pv5M*%jvp1|Tq0p60k zeA$T#<3t2VfcrG#*Wi^G178kF9GzUdwHC_Kps3PTqMZAptM(2%h0=Sf%p%%5Pj3Eu z1?|6=%&xwC@M8s@K0lJ2#1W)Y9FqHfN8ukdi2E;Bf=x+hb9!wqeNJ+nw$u*OvkX#c zdh?a2IhHvDF^~8K@W+BWMGVRuqgU1NW(LE443zTU9{i&s`2VgeI7Xy>n8evj*rAjC zzBp(Ps4U`~d-L?QC-A;?Fb|ft+TW9Si_cBww(T;VZXc2#-bc7TL6C^;v%T2tMY~>b zd~;i@)h2GwH?~1f`7H&XCcqQ1G5Vs0dp9tDH@_hcgFT`)cv)*;9ZX47LzEnHGf|W})<`MM^cd(ILL*3RVP$0!n75kOSs^3y1OMT^}Rv ztKFTT{uhaAxB&?AxGhMalwhG0!2GkJLIy4xbHfWkoDzQTqkE49s%m;ae2dV(v;K?- z>iTp0o52Tlzc8@`-Z+!Bc6JKPk3$Uxm!ZO!9@>w~lz7I)>QeiTlaMlmOzO0Qc>zN6 zJNq{egeQ5F!UN9j;^FM3$0GUFBd?LF56Y>I^B5@6^X&|beM)#f`%5B-Ix^bem7|6` z%U=$k>>TuaA10ivT)6B@XWk*xu_s4CL#2jtYN;8ePP+`#6~neLxI~+frcOKYX&9IL zm+`dOH(WGt?iUK8?D4quEUc{gfaLjo{V^+sV?I_uF>CXNqRZq8i8)0X(MK+126|3# z`NB-GP_i&l%om7y@=w?5kwQr)mbQ@dkwEAYd&pQ{job_Ho4MW(RBzk-&H`ZTf<|v& zvp)FnD^;mwv#H4b^+oV2hN&2jJNZ%OQAuK(?%Qu($+)zq#&Mu7tc7zYd-_jX4$$5s z^V7U~2&YV>E-7I*Gv+H0Gsa^%TP54cNCAdlm1OImg-!Fynj3-c+fzyyD+=b*#uKUo zza(|u*9k?vR4HJ@0@I+_8kaYu43dV5VN8x2ckG&?7!a%p-9Odqk@|^Y)d@&cm{(K) z2#r7~t{(YyC<4&Tr6L{eP2}pJ1TSuvhm}rscgTR^c!WFqh-3gjYbBpiz)Z18 zHizOrNCq2w6`Abg$aW;Hn>pF7RWm5ZSvvCi+kh{W;$+({HPc?FHsUQSxMBBJhxvd4 zPkN&@3dWe4#OSxdKRIbJc0LDa}j+TVHzreYC`}YpcMudmXEY^Uj(j z2w2UZuh%b~C#E9a@F4Dr$nCH92aEgqmfqId1l%DHBe@iDY?U!~j?|Itwk#glgb`N9ioZBD%j z7Gc+Iw6SbVG0lhTF2lN5Zo5Wa=iG0`sVQi%3FRl*E@od7PE!lmt{;s+vFPY@?T_P9 zn8o1Y2yGG*NQ>Z7pl+}8Dv2=fxSsx{mD85S;cfv2nZW9V+=};P)VRdLIt(9Ehp0`! z*hL4#$utsM8xAb(AnL4QL!`8^Q#g1kd91&lNrF`3c)n8(4O5!Ys=;L|K!rAmnoY+X zZy6}T`RUG%!SDj@Bj3ehgG-V?Wo|4~{@ZMptxVApzf00_xtn z1d{GI8q*xnyZQ0&+3s45%+dwnI^WoLZ;}IZ+JemZM0{1AzaH(2P zbCCLh(Ze)x$?Eq)1eeB3BWq`VTA=>b z?%&kK24{{fZ&5Z6?D0}U`^eH<^zIwFP_>+_9+}7VUi$HS^mW+x3I4=d&9-cT=)t;K zx@;gdpH^iX94*2$a>{^q%@5X<9Z(V~8ZR>|Zqh*IeUv2w8@124Q^*gY^h#B)`hQjk zx(M-@pK%~xm<^SFeRcUx;Y==l##mYDK#XMGH~~vq zdWi#Ep`cNU*MR$+TjRqFyTwNe`v%b)EmGZ%0*-HjBsEliC~?1j;~wZCGJ0gPjtQI3 zGU%!>VEI-b>{- zvNCcDAJD0kDI^&IM%uy!&ce!{Y}f8dfO`mhbRj=W_D4CyfvPcO?u=KqB82Yc$Am7Q z-m}ndBBjo{mqF2-lujY8h1-eDPn}`57ow)MxJ&_YLh4N5rovR;b#IKpgvpa*%yLN6 zTMast-c{yR-HHx}Ana*0EDRL&@~jua>FR%NwRyYP1CF<(4y@n|SpKa75anRYgWNZD z6@13eYxRcgLWdIm9yCq<{72BVX2}K>xubmmIe^!T2lC@hw@Xxe$;Xuq(-18t%!;X7 z-t&DtkRWKHl!p~tHA$y{$XzLd9M^j-K6;F{TsijB1Z)yUQ_d_Hm%w zZ4XHj$@5?;`?6=W8Ky;MR`fkWQRY}cu>+mo0FgIE)kNK5K3S9kr?^n8^-kp`ZQT|B zL}zlN^V?V-(OM*=?QaCC#d6XLMvs&kl~;}DhsEas-mRe^bM1AS6lV{zqM28&H1d{S z5E_c=m7=P!90K~3wWaw3p(AV=`?~T^=bNQoX_02=1#xH=g zJg&-v8}wF~d3-zv-s4>Um6%t6#uW&p9CY-&Y}5vrKz#lL{Ca$x@|p=sOd!v*C0FW3 z)WX=Ni@-HB_VRSA+mhZiQuD%I?KPiXq_*|G%{6tt5K_2YEwED4^9wQv0?GUJP_L)J zPDJq8_U=uk(fS?AM+bif$q%rz0pLYfl|KT%zTL=@DQ|Gwx0ak9A-mLTj8FNiVD#_D zdU3Ki2t^1pO(h#o@Kj4U^Yd%V)}gIL_259ipZjlr5H*jVJ^p(A()<6#`%|q746afF zoB0@8|JncQNdGu<{_!_6fb=_=oHpylfnMA5qa>4KiN!!Vd7UWWOQ!#q1^o106jez+hInQ5vK)p`{|&cg zB)yTQR;CV|`0`f%$7T%1^;CvYt=7P)DGFW}E%?nK*-=Y7H@-*OOY46pFlhMw-34TI zHk{$uVEI6mK$0i&ztbdCW#u4YODS{o>FVegLTnn}a^v%xc>f2g^*-(M-JhR+$F*Lm zdd|P-4)@gC5Py7zsoNLh>l6@EHlm#V>ONa>vLIw=AJ-xL!8WDpwUW1aWL+tw(#%eSXJFCy|Ea|Wm_@x==sp!!zjITpoVJSVDcKws9a6R+x zotF_FZnj;vU3VmmLr+n_iZx=WI>_|aSm<6)UjVyc zw2$eWnA!)|Pn^1*`jGVC?@65Css5w3gN19a=i=Th@Q@FVR5Oy@q=#XF|8$QoAFE4% zC9_v}Dw2|{_x_8S2qYNAi^h)e^pv7pWJ*|~PIB%^vfp0*`7ksVh#pYoPCb@!4!Qw` zN&X;btpC8HIH=&@b}8E!N3JfdBNi=P$WaZmi~$xvDKTV>Ben#rU{;(Vo?08dND^p} z|NYxB%`vyHm>LDeBxxMzOL`!x-2M^Is8nr0M539{e@6o@<&L z)<@Ka);B+jw{<)@{r7^ce=gtp)o6VJ^rggr#*&|N#}Pfs4`G{O-UXdRRv z+=*ncx8B!WGb(Wq0w>4HY*=UONeWi_&WX)<^s~maHc{-}_R6z>$X8sqXKX7Px3J(v zf1&NRv2YO9lpx8fbjnK3apxpk)Q6)=KJLWXCkV-T8+vEN*-Qr8?sWc?@bC=@)_=R1 zbUFIUMZNRHLMBM!D*OLmrDlJxZj15${PDH@?_%4agK1+W=Hf~*)rB-%=O z>qVof>+R5=kpgWeD+<5PVtPa$Tnc!BH#bD4pWsVr-sJ8zz)?FmE!*!GJI+{&yy^6g z{1gv2A@J6q5A93$W5>_eb@IU8SWL7)3u20$66~#8YVZEzFtB{yrh&@YT!adSPt~l+ zdT!$rP7)DxH8cJuqAPJL5vzbWLp0DPuqbQ(8SwoA_$%W3eKlV$rB&2@a+AnhoEV<+ zW4N)=4UBtfoPf+TrL!wbu&DOs=Eyh<@!7f6R@zOB9qIes$GQ#MtsEvJBgZG_W2CLU zQbF^{2GM*6+Lv;<9sPiaSKaHKM+rLI5`DCKS!EKLp1R%-f9BDSL>rA5cPKY1su7;S zz~en8W*C4Iw0L;nnyl-9=v=-jU#+Yt`hMh1zGwYAw;npx8=ICn02`Q^YR*yWD^sA( zq_PTO)#*?#6-nStYK;`uvZ{9u0~X?~k5a_I)D63)&;`&>Xwl`oJb9rz`h8m3*M(xE zhT+d+8cW!a+%lkZxrHV&yc3$bQ@;G8vgQ)A9Z7u5@CnJl3*C zqW2YG+&(B}+6);2RC>Ht*XH^6G~uxLbzq~QJrr0xCfJ}WgKq!1JEDgVn#^1IunXb$ z6s)t1bf27)BE6+OS%`5vim)meRlsLra9JlP`e+SPM)<)Hx7c8|!H*roF@F}&Wwb#z zFGM@r&?D0&(?jz|rS(588XSB3-vyiAlxPO;9kOYG+I{8eNA@44M&zk&xC4Ex_ zJj7NVD__U?Kozfr6>PSxD=6kYjgumvYSe)Ql(-+N-2F+x^o>aG(2RH)55WSF?x?7QRR8Y;?k@$54E_(%XtfniG zsVL`-(fJX>2gU}eoOX^FOZ~)3tRrtlioqJU9_0>UWIly)fBp*@_aIgQifSdh&wVi~ zx4PMlap8im$nmjyfD>Igy>*MJe=|41=&`fMMVkbNi(7}M{cO@n8Z+_>>0R?wf&Zg1 z@Z)58Y_B7_Il4sJs7;Sl$AQYx%!{9CNW+U{R64+FP=nbg==9qOm%aLTTq@ZYDbjhcMopB|7HJEiC+{ z$c35rlsan_`061mTN-RAQw)tO%Qluq7V6|VF>9yYoW`3knj1CxsV}SC zm#h3lQhUBuIuy)?cy5qe&%+7=n?DnpOEK~sr6R#gzW_{N87%`w2an9U4?*zLuo}kt z6)?S1-f(d1$;vfBlq*V%w60(`ElEz)a+=%nX16> z!d}1dL{UAyyx1D7 z$D#o$x-UWh`GjUI4fzThnPkW!m~1;6C>gEe=sgUT`DTw*>!z>kU_UDIa zNT!c4ZVS3iSdAn~IeIL9i@iUgA#Yul0kTgRcIHql6r6@HpDniJGz@x|QUu<1lZ)f{!DxQhTyEqHuHbwc1&DwsnqSofLJ|Pfg>%*H2ljc zRICNAzgIM+;DnK>wiJ#iN_2_tkZy&@kQ{8C->m6^g@>Nx)I{8F9F*5hefxyu!xe=R zx5g5F`Lv_umV2CVC-=oYN6wX3zveMowfOzC-y6|829hLEk(KR%IP;$kR*z30FkYk3 zPkR%W=?G3d5RKKYs2a4xkU~srlA@qW<)diXgz~d6t#mg-FLt7$f^zQ-FF|?9@jvZ| z1TAYmJ7vUWI0oUeJBX^bYJu{e{OTj`ZL-d^w548&GEmYwvQP_p>I>n==MDTViZ(IW z0NG1F7&8(2bka>&EWx}1q4pznpN1ElbXPd)e)<|CE}_`uwB=?wB*0g+%A#QuM35gV z$#Cc9-J(c_uy&73T(%fQKT?O2Mmgl%G4X&zi3V&Rr#e0|=ci@u7iVIBT0PdqMv;zG zL2^5m!i6qTq!XRZXQh*AJ@P$uYDOvm2C=2Jqs$^`~eI z!%GZ9Pf}DCn{oqDVGR+yBLjd$9?(^?H@ENQGo^XS)(2kwNcrTSW9@+BFJrN1Fw zx5NBX+HhefhY}%d7f+JDE46{4ZfMc5iwNzSPqL2un&UH*uH{^s8!a#1g>pcM0Y1aAt)ahKEKDGNDo+O@S|>&Me^VjvY}jwKPWM zhQ-?nnHS_EL$6RDiz>(!*nlv+W8+SaQleKMT7{i=RYhpXjY{%r!L)@7@9#bc;kxs- zDVgzDdBz??tm`!^d5@BpH|e*NbMt3mjSNm4TqFSb`O)Nb85F!3rK+n}xUJ_ZYV!5a zLY!jtt{N^LgWbGS$Pm}tMiYn-3lJw4NLRz8Iwd_@^{~jR^$#AG zLpny2Cl6Y<`{Qp>wWhw2xp91snQp21xE{A<4>usjhkP5(!1%v?wm(WH*QTB#<(QO~ z^CIaMS2qYAc@~~TpphQ&XD9N1kQO=^FbgW8d29KL3o3oTNu0^kJd1B7EWa>7eZk$| zEFpFvV4}>F{w^6kHm}2@&#wDiV(M-`bkSNnS)m%0)dega>&gJo3b{fxpuL^JPVK7{9(eX4$0$(JRbZD zJLJTSC_pWI<~>&~I73PM)#U4e5|obM2)`PV> z?botN8%Cyn0Z>GuH&xl35fHodfaN#&SeM?j{=3GqEfnhH%uh23-=}<>Grx))$E4={ zq-c~(voyIA=Rf7dXEFI)_hY;unKO0mMJB+PYc8*ka_hA^TfS|9)rFCS2nT`8uyILi zI-fzmNQrK-UB21&BaUeY`kV^GtX+OMg0+TW=A142NlpMeX)J)m;8p*m<;VpY1*5_d z$J8ut;j!eGlFES1#w{mz6u}~WKDUd*r*_~#D+2Ft7gl*k%)I8&zjg6fniSLsL5O8% z1LG$Dv!K9XEnWl0D>x%~NtAcHY1-4>IZ1a3-u()mYWk>qS?EUZ@gk$O)P8!hPJo(` zXwH2sHZVpu-??*(Knj%r*W9xi)tG^gH^fZ-D8;c~H*`SNfht9~XvbLyNKK=J(rC^e2lpU#tbFp*9!|9aV#Gj+v#zjb8b5QsXHB-XBBIXiiRvZganfr#_F7yo$OAQY-Fd|utCao*qHjLp& za+dsX{g`*|HDj0YU2!mL&k|(?0lC1zx!QPmaAvY=4)cLuCqf9vsPZ+(shXsa)YKfe z;;iZf`U=;czgbTH^z2hV$X~b12}w*X>C7)3FRQ`1ocHN#*|E#3wuJuJCPK&jvS*?butM#_`(L;K;s?f?G9413)8={D6X z9+Hjd#JJ4ayrD-nMV5tJ7v2N~Il4KklL2$|PYXm8iRtyrYW!TNeZ5+?o;GQx(|DV2X{PS@#k}~w|G`tRX>0iLTn9p~=UDW#p&@B5kCx%z+(%75rC$HMBn4EU; zGG1i2LjSb+BUSP@aIt*6z@SFWyXUbM#*Z&NlGQzGR=@`T=J}N}^2qcg1J}&Uw_z&M4 ze6hH-{8j+4Ye8b?-7kQDVsihT)&0lwd);1B>C2C)*XbAw@t(9&RrtR;9)#0_>>JxA z{=mG2_cQ?c=M4qXs*_6IqqS0b9(+GU;OzWUR_Mk+?MOaTDt~%x#1q>gAYVemhyRir zIFpHPri6Z_30=Y6*l}Y>P5K=89CGyE9MqjVS`esmg2P z>ARVdJ!rls(X(W_7R@xE8eODwtUZ1aA5^;_!y0~_F(&+G^k7Og$*VWoSAFEIM2mV&U{qWSpLDBZoAe}oe+B;&>w zmLg-;hKqsILM`go&^ZD>dw<2ELjSu@y=_*|}V^5#rzsaFrv z;%fLlL;tb=@e*?Gv>MAJF}-Oh$fRyA>}2M35vXx~!mYwhqkG#s_&)Xj1Z@Q*^vIS9 zGQw(Xe)m5r4ZA7qgzSVp+CrX`8==I3Had)7Wq1jq&+Nf-{~LcKJ{4{bI=7py_qoOf zKZ372&4>2=+R%HBv>BK}k1VedyF;?pKiR_~g9nFYhhe~vza`n0)2Y8o;v_lwumMG*6(4v1S`}ho_>-wJ-mEn9QPuaM(IoYNj~nnmZ{jLg zLR=xbVwLk3K;y?dBZ8i%sZZP;XCG!idn-jK6>GC(=!ZMsZnj3D{N(aSkwQ zUj^kTm)_E+X0LeASq&y(M&yL9nDl6A=|R;n=-1*Qsd6+A1rvh**j~I6eS5+%&>Qsf zNMl)YLJO%ir6sEhnX`1YSnFt7@W+|?QfA42*x)6henz6(X}&U$@L~;ch|^0# zb%zSA{ru|1hHddC>j#>O|j13JNouQaC&o(%aPE zI(xt3H-)P;SR zPC6?jXeTP_nO?Sx1&cNJCI^a{Wk=U(sus=flQW#J6QpkEL2uGIIuB(KQrRvx8rH=~ z$E%60=9KZa$Pdv}qzdn$;GKNZxOE3-v2gmDo~L4!<}&l&5APH<6kucM8xOa z-S&gm+$R-k=f$vg3UV9^3m14$>|*BDmRW_Cv$D=)PZ|n*R@I;t=Bab?E{vD3_jueg zAAZ}c{Hk1z0LXc|ibvS#4XBQS^rai`n-b9*-PD*4mie&ehqd4ew&;TU z6P{893}O65k>U{tN`noXW;UGEhXrk>Kti6(=pqRec;z^ff}CG1R*PR=SN3u;S4V9tw;wOg_1l?~vKv zeWjO>{yiWU6p|MT$E80o!_vU5pNT$`is^QzE)K-9a$V-UZ7$=-L!Oi{fT)M1))gNv zd#@iZ*i`XhNfc8tKUY$DDyEJdBT>Ca6K zV5Lb3(Ff_0I>Rtyv36xjd=^j9%sKc`u+boQ$ew;;6tfMJZgY~u(FOBy{AZx;r`1dU zj7ptw{Z5MgHzLpPH7YyuC+6RLcBoXzj*k@*FrtP5;E~;I8RKC8k5K-uI={QY(19z~ zgl_&=K5fdUvQsXIG%Xu@>*WCw1XS>~UG_TtNj@>jg%l&to(WJ!~EGe z4O&?l$ILT{yzrLss0-}i88yy}<`zTJV0cly3*=*&`Uj+FclMC~I-e#?QM4H>+1nXmR{6_;Kvo6L#?9B!+$s`kDtK^_10`yw-}}9kn!a>w7D6Pq>Q7uc z@Zpu35|7>&#Pr?Ivplodw}}OvESc&W@GUJug6O8l8=hQV}3rq6Bp}klC%1W*Iet565^%p>zCpxXCQh@W1`lZ!|SjwEyLeh)!Q0E6LvV=d3@!z9!nF>}8(gdvS>nhntr$ zNov|4ZjunXR&mlk%5=7Z+#gT7DuxyqZvf~%xCwF zf41?0%k)tawjdo`hakeXCBvH8I-P zR{$4O7GInsIK;1>7KC-wd|2jI;V_<5nQQKl=L_qzX+QbyD^~BKaWyK@*o3T(0g*nG zzTvZ4Zh_CS0wEbiIYCT`+ppvb)eXAZ25+Ibionv7T5`vNer%Gblt~m9ca(+_QMC_1Ey5aTnQ?|H~Pp^ufHoIIB}Yw|jgA4!IH+`g|#D0n73<_Eanrxi4rIgi#;UpNV`T0ik z)NVt(%!}ftV4YM6?!`O?#Y;g+Q5c8mu#5W~(g*V1$0m6q4$rMZrosZE+hwoid8D&r znR!V9S{e7RMDtrqNqZ^pCyur~*et1yc#LH~$vBZu z&z9U96*&_|ki`e7MbnT1X5f=a2k~0*=J77+?59i&N4xmkZ~sC<9pc_A)X6%=RxC@k z%>&gmY6|4Z3t~`byolvAj*BK3+6g;RF-8kk!i8Yp$ zsEG8U@m&5GA^UUc>=YNUYvr@ZF3DQo4Ie@ zQA0bySjOm7at5d1vz=9w!QcryEDozVej9WiC@Cy*$kY-0{DV6a577VZTM`&B0cek` z6`c^$NGEu4$WUn`$y3A}#91_=WuEXE#jHWcTi}DrSQ7bFu;wv$nE8P0jT>DF7Xb|1 zMG1@?u6$1|kiEz#w)MNnxV8Vo-h0P2(R7dEn-CyCfDn4q00AihLXj#OAoLb`6#)SO z>4<_g^iZWsHy|J&AjJYGO7AFLiedo~0Tm1Oazhn;%KJRu_jiBy{&Dw{%$_-O&dlzf zIkU4fXU-@Tx@fb}2h|8A2j>cKq%76WlA_%g(`>7sDB!IVUq*Om9r2UB`p~wv;XT<0 z6N#8?Tw;kk<<&l?DMVxRHoX-MEU8=%jFNueMY;mZ^HDo1HUG7XXYzO|%-((Podt;A zwL(FS<)&D4h(dA|PW8Zrx)up$_wu2==S`2lEH0Rzpiu$ou>|y<7}1@#`RqHP`9f%@ z17)5v=F&<`*8!=xo;<>rp4!43)Qm6#+j&k$9{#4Aud_f3F$?O*Z9EvUYck8uiH=KIx9_cO>+_~=~L!a zW@uq^uXK4?uM(}tH6929c$s6pfU$5NYtXK9_N2Jc2a+OcH$&y60ug~^0|T=EmJ7%G zRjISp6#*~V&--#SsI2b0X&S^3gE6DD)($uI?aNi}QBrs6E;zJ>>Wel3$G*R<#zm`t znmRfB@xvjH^BkzqurNLMoxQ7Tna1hnNsgcZ3T1;*+{)L(;YR$@Z_Ualo>(Ex%|#y< zG5!FwOD<_ABPI&q!FxIjr_`DjvqUHx3-jS7b7kUc<({>V=-e~F?_@=kamUBvN^E;! zed-S40q){NbMszlxTiSWjgLPXjG*L9%pPGr+kS`e< z8LX!lYOZKKrmL#5A{G1LwG68;llt4wK?qG`YV^+eDy#lb{eGA`guN@l`OGBvnrfGG zB2|cJ#Xi9f1O0rlP-lqQiq%o8SWufw6iZTIs;jImz8@R;fo0i{O-<*N+1w$;dZ>Ip z_du!0Ik+d7*gRS8nGY$!45kyNjkuZzuD{PU%Dvp<0D5CwRBC3AK6f~Dl`pB)DFEnAM| zQSy9W^GqSL&Jo>W*V@OmULKb6C^dZ6?kG7&YuW9hETJoqSt!g#g)ecLutm%`kar8Mj7zY>=x6AV{uwit)h2M zJ6@wg5aC8L%(I^*rE|&_vjXXologh;bTln?SMmHaT>{{qbqiLkxa7g@wO|E)t*x#2=pUVNB((X&Ywp4OkopctVg9A|{!EK0$xB zl2FQJBo?VNl>V^-EIfVVgDIgMwD z`5Kw-jGDQ@*-73xKFr;7w(i3T^o9Y=F9WEruJ-J@|45_a`Xr{RZjt?~D?1fi?qS@e z8-&6nXJc^Tdx>h#cJy=RiUS_LR@FQ-i3=oNs&U73lW}-0_I~>vA}=QTp>EhoW^5xa zxh=MvMUJb!<~&MOA~asMfP&AGyuY_9h49#MGl9N5)mm$(d;J19YgLn@#DK(+WIpd4 zli|ItO$k0DTp7=IG>0S!@r4MFN={QR_N>X{JD!;Rq)6dNRK%vS(#z; z1A_Ipl>i$b5UYmD_ba%?t5P!dDEu7BIIGxUrZMhk_l(n2-r;W4wlT(P8#!A)0nE3q zm^%WF;>ObsI!L*eq4qfw#VoON!Ucf3WAcMijLoU+Ejw@WkaLxp+JQ8@2cE#!06RU6 z`;$Rd{y#y+C^t9tM_fO+r4{SA(G-%2>T5e+0iE9LS>d zw+L7P-EDI=GYmfEA2MuaNykG+m)s1ZI3wmY;a_}R3S}zL=^$`yVO&Xp0!?R7+;M@o z`9pYe%^q-fW%uCwCt?bxczW8;2=D2!NC=kbz2(`FCw@+3gu{8T@ZC6lSoP0Q!`-th z?`^(kaUS5WvuyXh9P{`9>wjrk{oiC#dZhoWwx@P`;e(~k0moI36t}2`3=k&#`eCKaU9Zxx;^IGfKgPZ&cf+6B^ zRF~!{mS1OCe(kB91qQe*cFabko_n3U|L0(CW3m)GuIM^KN^-ltbj$?DsL_n*pl~VH z_kE;vb+|xiAbq>8#c2$Rh==Fs`~Y_3vl85Y?KqLW4jkU}Isj6^=*KcSo49h@L~2`T z9LPVuSwsJs7GN(fX^pe|J0A5CQg}sxFI+kM0LP1fpQh3;Ze>cRjV%s(>eWKd;}Ffy ztV~ltGL4x#bf&NtJy@K&P5Aj*iuQ%#lt!m8utfwsE?m}2Lq0!;n4~xqebQ|p4WEVq zyC!sG?nUHyYZKYa!;dJ62jewHtiJ;8RIQFl+`ErmKNFJdFp18`h2B{a$mUC4fmT&5_qROBxtwZfHG-NunL0vrbnFM8+}90EwQ?vr)0QySCNftL;&8+W=ZRzh1;Izo6(b{8!T@|qw~I*r~6`^P4`68T1WUn zi*_K<*bhsL?@^d>{^07)-)W#SOrjPDE1(f0$OJ_E%F@hYNzO!MCWw&@_Um#A~b%mWkfY zgIS2o+CVn<(k51e%jRAvT}WFp3x!^L{7o8NrMgop*ALm)M%<~A^nvi#ypJf6foU1t z1YPv;i$MgZ+D+2ft(@30)i17p5HDjP_Hp zp}j6-JFnSJEnpl}=Nt=z#4(H>2t4S*+&=%jPp> z@6btiSF$6y_+3982kxDyZ|qT}ZCJ#TyxDyNVRucBXOa{ST;MpZyH)n3mL9;13zQaX zqIOT7E&w#ka%eIHTDFoE;c9kG%fv`*iZzL-Z(jv(oG*VfRcEYhPoRBFwe+q-?sN)y z!vz0&=kjjnFCf+&P?08lrm|qtili^#HCGifV(PnlN5i0_1EV02sDyFu!p&)VnR-lL z4YAWBh6G}-W;*XOfi}Iw(8ifdbhTwz@M)7>J(sy~k`3|_VP&Cxo=O^}(cVWuR)tM~+ouXsMbl3Sjx9b=d=uH9=b&CsTxQ%onNlExKzcJ9gpXV;5Z zYCb_&sWeb-$LqASfN}Wi0zTnDdW?ZXgHp?(H)2An<54uS&8|W>8|H309ce#vD4H@x!_<1U}FHRqE{+W2B z6=?i~PqBNE=GpfG(XlhEN%uunVYZR(y%UN;{cjYx?K2U)45 zWW54=b}wo+zw|Z*nmBHmnQ4$=)L!tR4uVrlji%qvfIDuVNb63Er%nly71mOmqz~j! zN~64e6)r>;TT=Y{oB-W7ug~5oJ=g$G#3m#54aj@XDSVvCgj&ali27IU}nPJ z)Z=+%cNv=EMqy8tT#1hmmRWm5y2tZu)YLEo5y2~o;+SL}Zi&Hp;kXxZ27UuVPH{u2 zeN8@kw2U^eVZyFy_PD6wV#U5|H6x@vPE?cn1^CEs{ z<%4&XkEh;BY{5!p7#0Nj!U|^u!-98{!pimBAdD6HEfT3T=K%PToyL1#Vqk`&t}6j~ z@ABvSbxlNfr&uctMmP~h57s$h#0}GeG6Bj9Sm|mHKeOBcgnfi&{TH!;YAQ1ZHfpX_Wdqo82pG{Tdgqo08(@cKrf&ST%knboSBnh! zH*FMR2Op%X`?nRdlVZ*2Tf660=kkt82j!LlOs%vh-IA(5C9|9_nAO3`A5|^D&)xHK zN zmIJ_qBSjhBy*c=lpj)0(-itm4s!K1M5Er32jVUj%A2RL?5i=@6(}+cT?}@gK)zWF$ zdtUe4_*>Zt_l{^AECU{qPoS`SDVGo zn~Qs#?9%<=;|XD_RE}6u$Cbic-sarNstEK@tu=ANlmwYPtf6ZsXjNXF-7(`{p&<@p>Y_mpJ^ zb|D?-Pf6nfKhfS1t8r&d-2d_EIZS%5HK~E*B9n=vkk4xP*57xxU~K3pEx4^VYnGX& zSuUGZw-kGRU=VvQs;hC0a(mBf@IS_#8cEP}`0c?c~&r)i%&A5xExuVYwI zhkxD)euR2p_%=pg7Zlp8C$QTYN|}+mN5?#)io*Gd_X%4pO^y2HLAZRr#mmGf327ts zUeCgQU%oDJ)VqoTtMt9ZSi2DQAmpiBj}(nd5(;7+5q+_$QJ^0Hh9T}K(#P%Uo~~-j zwz25|`~%~;0J%r@9(s?%X#ojezkT|XLSv?=7)QTw4gv|?!U@KSB#~<0q~yniBRt)( z!g3e%1wuG&;NB1K*6U*noO8ybM_!(K=CN(9<%=8Ns4rf8lwDw>bsBf;p5xnMU60Em z`v;$4QyFZSD5y^)6@l-XwLewX?$Kyw;O=EHsgZ49Twj;JEgTnK6@B%cC8)@OJ&1a3W*_bAn<>?|^5qXJTZ@aoxzqDu7H_Y* zs+pAC_r^HE!lc53PB@|-%A>-T@rXmGg%5$|6-9(#9EQgc_rNPy3>%FzXyXL@7@`RKf>|6E}>&DHuy9Y*7 z@o$pJ#+||yoVxSY)+abbPwZE>Q?|@!FKwS7vNXkVdUNPG>|~C;V*dhF6Z8H3UI%NR zJGVa?f6s4dduhpY*FnsGm-v|s55KRq+?TXxv<}Gf_jwOfIbLd$wXw2;0P^fD4m{z| zbaj~dE2R?FCP(_u7j_e6%k1RClcX{}6Tb75B9%wNsZyMk z<}%@g_njU~8e?@n^7Jl$p`-liWvbk_>eof&^Y7yaYu;@w`dxY{tAs5%#X2$NbuH3j zP70-0eQnA{!43Q1JanKfu$qms5)+D%QG3XiVWfDr=i&>u@LP9mDXRktio|5-qzcVq z?gLjV7y9X8?=;o@bLMRfP@^lB6Ge~bWM_xp47B2JA9O*$Ta__#%qW}q1OkC;2P3%; zx!u<=nB}|qvLN3DMeDRg6J|RZ`pB}T=_qB*Cn0XMbkg?OWy&CWmt4-zX$t8vw#$zr zAl953PT~uaI7kqrj>)He4_?*5t)=8lMk{k&N24K!UTUBLbFJsWptGFa^BnOQ`P*_l$NQe+aWNxtZ*6O`((rFf;PxMAslZ@}SX2T2_7 zhY2Z8>?>%r8q*A;YJBhPF_Pc~g?uN@d$a~+uR9}M5wBs1tf0YiHBB1T*zpYQQsr(? z@-js1euPQGO2B9pb?GB=vs`a#n~^M%G*iWNW5tt~2b4}(JbX}{w|V^igU0AxWiTNb zbST7T{%nZQfLV*a#sil7RF!+49sa-vxeq;^&CWi|v0ubyRbvO~wFV1thZu)Z`sPtio7o;~I57 z-ef~8>4~sND;7xTW)#yw5)4#wL{v?VhkWo7M&2*Y5P0v~M4&p(uhfI5y_}D0GJe<5 z?Tn<$4EwlGkbsnI9BOqhXX&W))E`C|l=(Hf+HpAwXMYlQ88TnNRO}Lt2;VWs$|1tA z%DH%8?>D98>D zqi%IQGZ88BjXJ>eO8Lu+8z=IYC$2l5j9e6Dq*Z$Qw9ITbGk^1}d#eomnq4CuQ{Ce* zv&-)bv8J|s5bNYU*G&Jr7Aq-Kyk+U^ar>{%fpKaCCziy?I=I+KNl^ zSd3Axqf@I?gx72#lH@g{XVKPLkL9Um-7DYZJXV0MeAUjJ%~>vXK%vNnKY5P26q6`g zhqSGe*5?|*y(mL#J|{G~nFML(^)k__qZaVZ(E>L1p2N1auAwZ(!L=+*Hgbx(N7-J1 zV=OEDvuLk^6T?$91UZ%jJZYe2H|ajV&MTt1c*A98ei9{z9>)p<9||?b_+*5hCACMB ztkvG8PQ_I$N*X4YmyJ2VNes?>sZlCD>T0oERPh-a}f zNP#ekC<-SDi7K-1p``fYk4#2mSoC-S__6^{=P#F?Zl+W>>_{J^WK4$iHdS z(KLK@_oy+uWv|H0(V_EBr>6G3&IX|zMzLQo*IoI~gx zI;iFo(ykEN%+9CV-`6FLIaY8^M5IOUkRvg2TJqQRdJ8YqB_Q@pWaml)Zp%(`!m?3w z|Hqd%kY7+z~bx@OaC~bXTW(ODB(|hzBarW zd?#mkhX>bv~UoxrvD_<7zjTtycklA^sl1XE2+r08F0f^iD-Dktrp`gdC=cmDubRu^#h z?{#ZQlr>H;{Ap-L_F2ARXFe?rgi|_7_%7^?kg3dz>v&qesIEj5vtbmUvzG;d&-do~W+I}T+2sr_1y)203lj~4__^;4oj)$T2ZON>}Z)w zbq^Hfq1^deYM+`KC*~`@mSQx#_mb_y1GFksI5DtPJZ6t7go$}~dbwx+U*+%Irz<;zga$XFMerC5`NeVhgFfn?f>*gt3f)1vBLkH%TK&h9Fml#L{e(Ud-OV3y0>TO3ZxIUqM;zr$!B zu68^b9PTcY&X)1!@-ySF3;S}l-j;k1++ytW$M$$Oi* z6m!T{<`va?v%~p-3FDS10OPjEQ3)2O*0A?s&cKMkANn-V;~M zsL(>^s|$;r5Gk6bPiYDS@kDwA{_*N&y6K1acNj5uvj|e^O7$p5szh)_j2rR! zRQ63iku5DY%6bkBBPf+ynoM)fw8s+B7RWCbbtRaYt%^_HZ6jIg^(tO5d2>v-j!Le@ z6?b@F>fKnSAU<}T3y!5l*3!>~A&r4k1zZhJSjJDX|Jpu%^*5U!xD5u)f)G!peO7%j z{61s(&}Vw8wkEB`4BvISMZF zFkTXkbG%-{rQ)Uk#>|SsMy-u>5ZV6mW%X0xPgL5Fb4(YRNE|taj~PzxEISV?EZ}9z zW8dn`eOKP_&N(g-fKRsCpH?MP!LHoQqYhEDU@Bq!u*W>FP`XdQK&W2a4K}JCC1s>e za%beLiCNhfn$Q+3Td*t`6Re)9X5$;};@iV=trYR*sFMv)DELY#fD;;GrRQ9ilWlP) zMnPJC4BIj&gWzLexp?2FC;U>Q@_=VX(tRqX{%BS1hNfOyogpV3*-Ht|5w8WvgV?v2 zGLlu2%7j*ARxqrXCP&I=MoRCVWj4Cm#rEUG?oi2sVQu>*+#vIa6x#TwYOnnr%lN|z z`YuTGSyNVjD@sqLA&Cgrt3H=sRT7ZpPAVIM56EY;%t0Xds!{Lu;mKPM$xEiHSDRS-_r&P| zxuxN`Wpbw#6ul!Rk?OtV{>KHAo${`4SSWP3g-^Cn=KFsDlJ!b9k zMIcwFIJJvcGv_pyPY*a|NIzoQLMD}Tjhl7owiO;}6RmfE1HKl!;_T;sdxv$y{fhDz$ZqrA`WJXS3BXUTtoYDvR1YfOuRLE8* zR$$g;buHxOb9Rj+m>*}72^1bFVU->;u{XIr!8mJpo;_K+`#r9{NMb^|z)kII9;DVE z&xU%-1u)AGXz!?6FpKk_Djfk9O%IZgR1pUhDsnwuo-(_I47`e|X z!_NF>-}%KI6DROh;o~H0wDHV|qH!m=0j86!k9SPfR;u*Oa9Z3RhmaQrCckz1+RoLT zmtrW=pDMvKNL#@N6*a^F31Fw9ZvAGKBXIVLpW{;@C>AlNUIiWs)c6$|$P?8ly~CK# zJDxU@^!UC|GH1$!@Pk#M8a!kDdNq?GL!PHWq#QcP?o=^r0zQAI)=Z6BGf^8MYW0&h zPX#igNSKy*H5Wc@RDRkObz1lvK&^Uj--sB)SgIjRL75klAI=p)-_`W?kd2=nO8x>J zr9MYXdxeQIh6K1YH=Zt>5kcf<4JVJoN$C8dTkm{!sJaU6qNN>sZg8&Tf*`skRYtIi zYBzi1gDDLiX?J~Hm1v6VTLzOq>vb{OQ~8pc1l=W*y6ldW%+$o144cl>;*oN%Hcufp zK!f(Cpk_MVWFkD=Jv$Y=6jAg$P|IdkCnGVW9V#nPlzlE{`g5kw z?aIWsm(qo*Y|mYGU$k{HZTeK0ex*G=D$t9vInWKkY!GH;gk@wC%UU7>HvOtaek!u`iRu$&MuZtftr5E)94%WM=B2`GHOn4g_t6?#y9Y3_J#@?hSf@16k zFoX-Aj%2o>Mf0P15U8{y8SI-jm{&50p@{99fGwY(j!UeZ+PCs)umRm+4pv$3S0@*D z%nmvq00nzJwpz@$xRhN<-Z}D2=hIdHqQCZ0AHHs9I^qFO%~lGn1+qV_dSSlv1-I}6 z;2!pq;_46F$ulXXGm1rLt2rK21#T)Wlga}dXb zwNoWksc7RO=Z`-O+?f}3L2R57@;aJPC0P})1?*)3SU$U5^Fj4_zE^e+j7L5$V`elQ1A)O8|2|4 z6uO|wRBwqi671pTcX?aNL2v?fxy(wAioTx#mok~`r!EofHXrmg$tiruf>tW!jOb{V zV99)S*XswcGnK!VAp7-~Mf+zutzDp1h$^#N%@Yn%!2Px9e|4*<(_MQl6e8Y-zOPBePupNzxrHaiC ztC08_EZ;~`K+glm%kXpB?(Z6+?6_mJvSq+fW0Ttvl#js-CTirRw*G3+J1)l%HXcwa zeKu<%2mJ$&{nfL}A(8s2&F;YU^s@nYL9}BkxA83weDb9uT@MfeH=_wiWU-nMJZ(St z+PniIfi5xQ>Zhk9?Hr)J?E9_(bpd0(e0sye?|RE*@3epHZ^V)fO^j8Uu?2D>L~a|Pxp-dW<&b};JxGh0_)h~`LYO_RNXHb zj#Hh(KXI{klUXd!=A*qf_LOml{w!+3w39minncV~sIj(X)1eD7eARkOCU*qeflfWs z%$&Jdm1KrQPYTeoFY4O^sHjY*&1-TLSA1qEa2{x2gZ34Q%KRq0d` zZK=7825%QGCGJXoN}nYCX>>q$Vyxvwq?%j3mcGIZl!yo_LQm&yeM!f>t%4Z0&zUmi zStyRpE6o$FkYo)vz%fal#Scim1oK&gV!{yk%OTWzA>pkfCvzr`uFvXiZ$9Xsd zf1dfa^3U?S4CBp6p|7J1s{1 zYRUAmQsA|n){}pVzBDeTl@T*9)$u=J-d+?Yo}~Bsug8(dZFib3lXVBurb=*6NWL(g z{||t?bISI;n4+&I4iU7jV%AZ#~hii@%_W+O+cdLh4Ejf3BK1{ zcG}#@a7OOqkjSCC1T9oF|K3|tf3ZuNBBjfIgmlK>l88y+@)teYb6XcY5jCh(;+1h+~@(( zVfDNG!uVU+zN=dAOTLfpoV@VG?2O0Re~GFd^=PE*L9=e<11{n7&<1+LzO&HpEjuZl zOgy3)MD|1V0~k0RaBTX~mN7rM_A!zBIrTpP(yNvGN0?uk_}_~A%#n-u@@Us&0ez*b z4wLi4s#ci6B5oGry7*2bw$DTA(@_q`XrpSLrt=;VxA#kf*bJK^IeN2+5jwr!P9cZF z=P&F$=NQS6r3Q~~-kp;ihGa^qa*UKTDwmWTMA^*xRT{R!FlP>`E4h?TaD;#Q0>iY0 z!y>%TV|j7Z%qO$olXHJ^jxX`r{xY5`Ej}{ij*&u&C&jGK7El$<-?#AhAtR)-@JLlo zcfd+OA;qfj5~l<4+@jA3N_kXLcz5QI@Xear$X4U{)0vO=;jkd|idWu?H+4xd$1>^RR#bY!^)z*RiL)*1#szjBP~3~#*bkoD0jt{W5=4ixiC5sM$)ovAL)vL}kBI9h!jc^og~F0FKf zoO#Jt#{@&@)bmKCx*K8p63BVe37t!~Xg5_JF@s-8aDv=Ef6zcSbMZr}sjzMD^MaM- zrfBGlH%Ixoy~wELN9sD?)CiWs*&a|CiC8^su7OmdR@D<0K6AO9p2NGiWxg(bfZ ze*nQ>K}8>l{ibqt5+x={@_mb+KIvKF59r`KJNtj*8=v zO{tfiQ7Uh^T&{-_(=-P{S-CPz9UD9kIdodkNL-Spoar=$@1c>=k$5u6GsLeReqXHX zsi{SHy@Q_d`Ah7w8P%z@b>45j=3v`y%Fs(=DIU@;anR@uo3moG;xh=kFSHx$&d@|I zrG*2fJE}Nc>9pIbUBFPGtqs*&oai&I0bN$YoS6P8|5q784^^T4^KCO~ zyUY>T^6|HifC+2D<07mDUA;6d#n+g}@S9*bfis!U%yY(-EfO%l1bisxV6$VmE`Q?H z#-!p8;MG2YY@5NDIhHU&Q8)tW!QC@$P=yjrmM8mclbqRF@v$k6D49M{!7=7W! z9hDc*P^|#rP|{^gOK8g7C(Ww!t}=$cTF{1YRzL(a8rURr^TWf9*8KcJTZe4{&f8KYD-Kaf%+YuuO0k$ zshl}T?gZ!)4V3By`a71j=1*7Fa_7_&`)&7o4e!@T;xx^$y2X3wkH!GcxOH_JOvw(Z z$gTg>Z5kfO{G=Oguev^^U7q^#;SXDm9{uC&^26If``$Ph;=J7nOYDZ7-7*!FE{&no z4IlP>=l=@2xX~y1HS)z$1KJ{S4CyZa-ERe`=2NJ>Dlf|>WC9O92CGzOMVPWcG^juO zn~?z8iWr&P`Am=%5uIC#SC=mf=$5x}Hw%*T|w!#;Mu| zbagS59r)H+bnxx&@(f|cJY8zAb#(kQ7M?wBuSKQ7wcU8tDYY-l?=f%9Kc$C)PDUOx zvp;jhbr(+A-I!0|tO)@%lAG)z0=t6?1cgHdyPb?FuI_VkBv`aez$#;%<&JBFq&SUe z6UFWXbAm=q+!`p({Q%;0GOEQ-CBvhwPF9Snczi2}#V0yfv@E7wz&v~}eU#S0pI zj1_A_j4ZI(>CBfS=7CD_lR)v#`2w=zbi~H}M*4N>R&7vqNT=T~O8))XM+)t6zQHyj zfTsV!e4*o*HgZ4Z(qpqP9p>~(^w-PSGmdwJYbC0Eh}qS0&AyhNlTpl)JDqL719YGE2pJ|>sOLxaZ64Nfyfi@ZI&aN7U=`68%x5h%NVp+=1& z)7@fhkDEbcZ1OqaV)cr-_7exyiexsyCAE?+<+i#B=j46rv0xA#drUI>{jAe+@M^2ogkat=R}@dl?ips{xcUKi1pq+m4pCb03}Bc1u}e(4 zBwT7@QP%AHfivkB6nqS&PKYN*HeP$tFd!sk#cUA#ZQfEsE#S296f!W{DAjdGXyBEp zL-U`d%u52B8`03`I!`P89?>yc=M1<%kJWRr%NC!!jXF|)snZQ@vjF~}dORsa`jU2M z`3_Y#nz-7e(=V>-(&Q#nN<$216mN(V0xz6hU}7dW5agw<-+`eP|Anhyp|<>kEcbo@ z){Zoi&@&g?Hiuo{A7xeq+ ztD*uo9K#ASV=}T|-wcnu=^sdEbg;4^8FDR;7kWBLl9w2?7FA+j7;r#3M=kup(D7+kiNHqfDLE+ ze55RP$b39W`k+t2DF0FR{YUU4E$<{%?w7<_x8`;34`kjGTP+jKxi`hcgu}44vLVcw z@`kAdU3E1_?PYR?vEcY=>$bCnHSdYYEc%0?6eR-#nf_0Q$jdW-08ggL?+|jc{Mu)A zuhbvF$DJfe=y4H9^B3u@ovi<2vug!?mlcrnu^+%P#w1a;g@aZlV)1|SN%7CVMa(Eu zUv`OAbp8OIrTv%$U=$z#3{U_704M+d-|_#~6M%5My}Rd^U*G@cqRC%yzy1C<7YHY; z70`#q_aHHA;Qwb;O!2onS&PcxkZYw3p}gS-VQU~mj$bFwfAtGr%LkxsT0j39Qb2!= zlix7EBmQ-KRTaqxxN80UYY1xFkYP*vrZ5S=Qv45MP3t`6f6EHe#r|#jze!xL41n0* z^Oz+5efqyhU9Swk3laHSB^oUJ7g_#2>7NUc_V*G=f1k_0No`su{#A(JKh)2EljYyj z{;3cddjFp3ze)WwAu_UZQLWu0Y)?zmf0Oy2@%~YWx>Tv50OZL#CM*C+b^B8d{j-ez zF|KKyazlt<9dm^Z3_#fpL#`+O;}8_aQ`Li%R)?cR?z+n|8^lVjS4{t ztEq_fS_2BlYbeYRf1&@|2BXy(C6G z)ioL#Mh^cTrC;c`^ZpUGBBMY8g@h3n8KOd`B)ot?Mu2^{6aFehh$=1&yO9jiGl7B0 zFjeAq`oD)c$;lwMH=0);B)unH{O)71MsD^CQ`35ELx=!Cf%JlqivY#lSHP|%f&N81 zL*E1p|Nh=a0aEKlY=ql|xPgLq!jrr(giSK{P2fMDK@NXLL-`AGyAanC;7BZhB>W`e z!mh%g1cjO3elb63Hlgr!07HNe(xII0BG;lI{ATj%`Bx#XVj!n602H|jtsm<`1l_FZ zMgRH}q1z7qUKMT90OIrLO`_>#;2%u0^SY*RiYNh7d_VF&hv_x9N8r zCE<6>YMk{Kk0I)8^ZI`ggzk{?1ZJsF}0g1o8+*)Y?>doY}^L8Ox z0KZeiq(p&rA=3WBwHnFAvM{UvhF#UfKOWfasO>^ry?0(C-coBLMLOIbbszR70OUbf z7b2LjoeKb-hLURt2&oGUP<=;kC2;{@>{et0@CE)-6De1Tj}%gdDZo|ddT>xAIZqqX zAB9M@^Sv=Z5hYA$hdLlY2ZBf&S(BR;!YT;r=BNUr0RRK6s|5E}`YNy~M35(@#ep0b zI&JSW-)t-~+ZxW_3;=8;zY7t}PJol?=u7Sff3se#@-WH)-&PhfKrYH*E!?LCx@ajZ z9X6o48U=o>OIt!D^RC@H1xsibPqjX(<*pb97N9KqU5JpRuLyO3Qs($G(0q5wktzVX zpx%cWUdtNrT|ITdTc}{KjTBU)&`lt6{4X?-e2r@rm{IY1OoDOkqmRiUtHggQM8yzf zTq1!ZLW83^*Fe2*wG`}X0LZTf)Jxf1m-cBAzf5a!ajYT;tHIXMv<{V%pEo6LQysPx zSJDedYCm}TLAeBO$1>9(9aHA=w>TC@TZyxuhsz| z$&x2uZ)FTwgTU+MZeiDfwc5Ca+b+Z{g_`RaoRB6`=lo2(~m4ydBFNxA{o{!*nFBru?pnWE7-i8w+*~Ci|X|TK&kn?{|+J=J-A1@$10+ zl_nClv9oX7_%;-269zdE*1?UtB1g!ATYs38O{+;@f7a$DWVD+Y&xO?}uvT@}pw)m( zyn2WM4gfG@fHBp^4Be46r{x)?+0Pu_Z(+00H;R~Vd9zjf@^Is^%~CFG5D@{L$DaJNvaKyF zZ@Xn*pG7m@;aP_Kr4Zp;8PKfPb8;MnUC-*L5Z8%dz-usyxld}7vye8(}P_D|4GoaPE<}w*ic0fBTN3>Jq1xYYmfVn zst7=s_P)lF<*R^DBWpTr`E3VsJ&%7DZj&N*O%*}C5t66)-w67z*L#}{f?uQvrWwXm z9l7TS0@7RB{#iL&RNJJ;1Tg7uRF{;^cT^P{dY$yA6xZY6mds|};{n92jQ%OGO^P6W z0FGrzq$A%9N456qn;3)x4tZ=8K=?IB^$;Y@BK$YxuOxpFYg)&Xg$RPHs=~1VhXW-X z3j$Ol0b>ZJSsT8=N7^`VoKg;`gN{@0sQMNAPh#7I_>&yOu&IihJ)BnLdMb3=$D1pB z+ZV!5=Kla~6XJiMTuY{&`T6lywRJTx*`|NOyhgK4h=0u^i~)$i3y1bH4p#?fd*U24F?Vw0-)IcRFRt2%URXLzdXbMe$curT`HUAO`o~|8(AEL z4PTw@m<@pZQvE%fpb`=TeG%2_j25fLa zO@MzQL~s=gWR1i2wYk0`b`4|&Kq3HK1OV7$m>mi~6&7z{Xo;hrU2J#UG7 zk~#pU7?uD{^eC1*b_Juw0#w#tCj6OC4!vQj74hBHZF*#Gjs!GhDVh~-g~JEvq2w0W z9bHAvtcm<5ALRgHbJ!ibhS&^NFPIX9RSS;5#w1KQ*>I z<`nd)f}PL&SR#qs_oZ0wYrSXMCT+|{bp6?qBY5(-13$KILl+r*Hvlg3Es*a91`9Jc)&gKF%W%zQ zhzDIc2?~HAcvJ0-k3)bw0uBW>%AkY{(!m388zr!i&)`QJ5%QQ=$rcE4hZ43T+kuUW z3IbT2O~Q(Gl)^qg7v~$bNX%a&+8EscSN$*c-aD?TX4@Oz2?0U~n1mLJlElzkC{h$P zK)_H1L^=wgh=NM9i-g{#BM2&00YL!)K~O`lDxe}FB8UhIA~r-2{q4}?dCs}_p7Y-K z{PTW(lVtBTYs#LPHQzOBX3ySX0}-}9*$T}?2Z>@x^wP^|gWyumD+G=V2+?6s?PV{A z^a?KEreH%clPo)^rV|W9$I%aOz^$@YExBSC9f*hheG2rLyflxMflz$@wnEh52#|4+ zEX99aHj*tL1PGvX);qFzV9YxI>cm(EoNQ!qe){`;CLsoLDY7XF0DQ?{H-M3Ju*{Cc z6mB7$k+&2I0a%Vgz);XJTMQK9s@w8l=I;|QFd@?+z?=yz-AgnN14w9Jq5x>T7)U^t zkZ2O~q3BMMOoqNrB6%t2Lm(27B!CF8j>#S*=a8{rJA+94i?#`bf)!cLYvs5mL})9& z;@2gnp3R0xyyJ3s-cp+vvqC^GL>)Ykm-%4MfNf6%!Wx`4%I7727R;0yzXWGvC^4)7HuuCcgF*GN`6Kwd3J zH+^LgeGEX!OG5m!?8vfm2>^(f1{1Fd5w?oNwH%iSW}B~@BtSyef+2=N@oS!SJ!M&l z2s&&zFbfb_i-n-CEYpB_ma+l}`YOs+VTB8lgp$GNC`dGTWIE*L-K{T#u5oYXP6p(nPx88#P3|D*Bzx+kVsyMwiX2PF$vMk z(ZRuY;PeB(s$sRax?rdUI8NZ0u?hfh%^7i^RhkNY#0CvzE!(9|0yNhN5kykf1~M~h zA_Q2=A3Ddo>nxD3s%Sc=fH3BOI zR$-~lmyx*4Upaz&EI@>7ty&%CF-x!XXGMV*qJwduSt}8Nb-fV+ieM>2Fsv9vB3*5z z6a29OWgyJ!5+LAMw(Kw~XRuFbCu>1bD^cxNC*;gv9P1A6vQ<1C$JINr=lx)CQT%HbyNc=Vq)EA}bhD`^VN@DV`)7 z9gN$yq)wL;tsFsF2nE9t2&kS%_In4Gw{m z0ZIC5ZXi7Ws8fitar~>L5c6!O#xI+GW-~nqGPBJQbW;@c#uICMwURvAQ}bK5*?AZi z0J;Q6&I60BId>G+T~Oi62~LRqAW<4f`iBi|xW6FL0+3!A6PZ_9anN|MHUQwYVx2OZ zX~}Vu{vZ+9@MO2jFQlI{GX!j?Wg!A&oz;ya3abQ?nHjTJfDT&92SDj7&g$X6$SuYSfiN4QikBU7#y$Z=#>HQ4x%Z@XdgkQhpW}OWTU<5shNcty zy3?77{xT-=0SI8dI%P%xTLu&s0KU$N*`Efrx7z<;1fgaocC_cblg%xhJ6G9bM&C<0JUS?37Q54sg7 zE)9yHG_lGTH3LJILO_T{py+u3Z%}StL+ns$u20R>$Gmk=T18@7)5u(Q ze~}`{VnqDC+cZWjwR!Ps3INFYLxPsgnukVTBUdb&Ql3=~YLy_cIIa^SSQPqd$htFV ze}HudyyI5X!Q?6t4^Yak1C1*+7hi1xW_57j4^*9G@W@iyjP+8WXE!ieOy*yNSg%QF z1WKD_ah=G729Z)uIHpn43kk+!0q;2c8JU+Ag#8i}W&hqLtze5XMFpOiHG`OFq0f_& zB8HhP0FVQJ>x8((`)7xx*?!=oIm5wIi7q#@=}I9Brl4AM#Kto%8vrmybu(5Z1&UxD z6oF0n>T^!>ceS|Y4lyG_80+*Ylks1YAok5!v=&zzyqQKL$!f9Ym5t+R@Ig5_#*9xCWQi zEY_cKYaZC}8p)hvta;XVSCu6${htVt1uP*b{r}mq)NAVOMkz*!IO$-!TV)*$u{y%-W-}*%lR!Kk)M(f4k4ss%OrTSnC!eiLR^mZfANT8 zA`u382zLZu$i*h9ye8QdA^u;y)N)qPCC&QxZ0T!A{Cmj%+7HcATJ0?GRf4b{iT~>> z{5^w^HHI`}jV$;N3Q>yX%8JUL`3Zx|0yZ1P50O82NLU`xSsughsHr5d*YD1 z&AfJD@_`MI%62$uX?*^dp!k1M1Q3eaFePqSkD+FC2XA>8ybRP7vj0ITG8cjV!L74T z{~_#u%YZVLwcPrAVqoO|Box;!CAmfcS^uIw{gdKfrdM}(Rn>Bg56GaFI68H>SRxZdQoQO7tVV$H0L zBOAUVh7Ab>>mzE_kp<_u#Lp6Hpn3cPtOQ|F52>lKP8!=w$&{UVa@Cr*1TeQFBU_y5 zVU7cC{7pekRcXB9){gEjqn@RSJbBpyf?Fh>4cxv85rb9V(7V3~<%93iOKpaHkNgcB za5(nt?_a-X2Ii_pcFK&igT1v6UNMGm!<=0g@t@2Q_6r3GZgitm5 zfMZQdlsE>1)z{{F>cXnc-=k1?m}cAEqnxgMJVHO&3~ocs-7JVOCe~sSovh8mqQip^ zG~5e1dyc~xYwvXTmsA)L?K9iI zlUHA3i+9)LVUBN~{I8;b36q=3vsuo(+W*V>!mmxf4xKu`cFUjZ7<&Xhe7mdjH?TqD z##lD^PJjzLU46zUe*?K=;A>YhpZS3QJ0ciqYWZra(s||PueggyACd`GiPKflJ{LR7G^7SDwn3~Sl54Xt&YLYztZ zMroAAn(SDo80m>x)uDNdkgIaPfxgebfyRd(HSXt3IlS^{6ZT`8lZsrs7e&KvVS5%Y zjG1!Jk8ktmrNPzfNj=1IGad86G@qNfkPVLohD!Zw^uxE(Q8h+8jWqAFe8L@f(K*Kb z=6ZtAI3dTNB}k5KZ_;bD8=!_2#0JAy*hsO>^b&KJ92x>Xd)o)TpK1BRl0hf5FJ(-N zibc#9N1Eehdcqk_-*>fE1kS$xrI8<c9`s>JPk^@xM860)l@!7@VjJ<<5939WCS@}JOV%A zadg(qr)eOh;lLo6)F!kNJW?H%r_FpAL(IOS2CG$>LQjKfbH?H-r8q==l7bwrd|EB> zX}VZLdUUpL@|WT_Lh-+@gjGD+HM>9MY~xMe+tP|K_8UU3DuW8+Z>}efoe=lu*cK^$ z=p|~u)s$>4KrYS+-87YJt|#(fySIK;qHn?V!Xri+R?o=c@1j3i@9WQNyyOh&b((i7 zc|TP0apB16Q+XI-u3zLM#K1GY$4}A;C{G={YOc1EWvDh+RGsmp$36@7W(I4jBRs8& zmw@#$kODaN(z(Fs-_2g7sEQvm8mg*nhK*uip-5bVcs}Rrs1U$4jUcWN##ebG;029l z8ca*#@$}9evN40ggn834MneyKbj|lChq$J}jO>u^@p@%=Dqv6yxLfw!zi0BZrcAlW z?OWvyNpWllhL;o!znB6Sk!IjJNfe{~;DuG>6;JBo`on04W1$m8O`LF5spO1NJKK@@ ztzzWlTYzkH!5s~3ata+*1MJPIt9I=kG%tV9EjqG_-fwW_gPMD;3lQ0NF5axVw&8K~ z2cucBnj5|aZ=Rqv&LL5l@4!)UlH$GUj$`eZNlcMAnl)Z)M9MLIm<;i8ff2E|pXiY3 z&~0jiI}Fj^Y%qCgzA>fq!4IqaRQ(7~;vYmPUecJJ`VCYLR-V2{o9L!SQCs+M*-5pq z_a6E7;!<5y0g=*PN;1Z~g@|q{H3EV;)gh)84+;#ZQ0?d*cc5*LrdKfMBp@vM%0@y{Rs!I` zn^C-V6S5u}su-+l?ffMAL`ay%Fo$(DRwrPscb>!Mb?a+9v3hb_T;%#YdgIsT@5Kt9 z=1vc@L*(~tc)UTO4If1q?74E%HNc;Gxd1^wTSB22}R@?K~57lYrXe5YSo3q_S$w$L~Q=kH;@DO0O;EZ zM7y!FSRXt+Q&-q#ROQo++>Se8gfw&pT+oUO9*4^|HwXc;?xJ`bFbMIfLjFcA7sC?% zJe+wvl}(_q!u{&T7ia;DP&#qf#&WC>FRN7v`t*jYy^x#-iZN+Tw)Ut@4a=1HhiyaW z;}STk0jlm8CerJ|xulR{H~x2N(nSwxbQ01h;=?IIbbEKH7L@2I9Z1qrn1`=+te>~V zw>Ir`(VP^0!K?0j^IrIdum0BuIF5K~JTX56&%CP$`=g2qZN+4IoQFvZIimyG=RO5& zIR4ZjZr9>f8*by21_ID`GGqg9y1rb@v(u9flO-o^R1V$w_sMNQGfh;v$+wtTHWbA$ z!puDseZ5-P-vG?V9hdp;^3;+fvl?e<)7|Ch?C)q^T9z+KUbROrLBBNLi z{*MB{0h=s$BZutFBmGX~jQqW9mU>Z@{it8&{SC!Q2TJ$*@&z~+aKdU%k;?Z^4f=>D zVg}H4&xIbu4fm#7`;ZEx8Ob!W=q8;#WHog!D_g?2q~XL~pFG0nEFB9|qvT8j@(b+= zS6M#JBNrsavgj>)7p1Np;))Kr%TGqJ!|OK1SE9WUwm1D$T`-qFe3JcRk+_x z?sxk(_SS97KY7AnW;$i$rA*_Ue~)b{76^ycWLgo<-S7S&Y#f*y99(dvS8xTcB*5=n=k3XS<)2S?ZX>b9gbjwQhNu z&Ef~DhfiYD@P4?)qj`4kE$J#DX^@8!=WtgY9h);{Twhjt)>f5VIR3PJdZ5bTg=J^$ zq30(K+sS{p{%-~)G}pGH&Wnn8&a$Oh5Qr6tc7L$?&F9)Xg9GsP-a4NAlM)6qCMm<0 zWa_tC1^L~Cz1zp}Z?dDZ3B%lo`q`0}l~&F@zdj17vmGwd`PxxqcggiG?Ke>RBflXg zX~28WP(}2vulq`;FUJ3hvXl>f=-m;bzq50&GN7_Tfld&7PdpDbQH-0bS+*&++ZWDT z$)3B5%J=f7r}`hwu_)!&FAx*dQLDJPXS~(P?oCL$Q!oZ;CPc#|L~M*?G_m$k1-2!2 z5uJm*)lv`%$hV#LZK$v|!6YRlZ?T({c7jbo!YTM20>4m{6e6pneg6=_ z%}S5h>}Y453B8PsNPvnQR6^BCIQ?oip~36boakx%^743d;XLG#HXfv*SaeiGW>T!ymf_Yi=jT zCr)Th`1q0ht4}NqTsIjz6pwz3lTN8kKECPcSL%+j+wHnr^pl2hb9Z;Cce8wZCpv~( zR8PKRmG!7Yf1&tCMZwpPK07dOSrJol>=ceDEyXnBt~aP#)?teFC~R9u*vPSy*|i!; z5<;rh<-!~R9qdxP%~wx-IvCU`TT9-bh$cMDY zWNx^%*{PDMAI@+*d%)7BB|KdTuNui)!)^PdEd-)1EzgE)1h-|eCF+g(l)Gx^$ij3& zP;v)1v-fi}L(OB#c`5QJt`S8KCuF<0J2h$ZTZvLUd+jM}q(B>ewn^}` z##Zc(!EH-$eKeX+e{l1t$n}((KGP=w(LKi-T^3BFJ{mIyU(P;~XXCc4FM1r-eDwlx zG>JEZtw5IHXwwFJ59b=?h`gRd5HzmGq=n9CHVnS-8^9RU!ySQiJ!)QqHRVKY!dc>g zT*MVjEx>jS&LNJA$mppi2~|Z9<_5KCbYk_0MvMzoF%hZfNzO%4pBUEO?HIgn{PjTM z*HFVq3)#RJs#a?X5zc0v} zwJjBwnV+`9Db6i0)xe=7re!ACgY_k6RhItd;D&w)fnl+8oVBLJg!->GJee(@csBK# zBp%vB^O;(F5fmZvRxKi}k9digxx3!X%Z`s%u^ww=gp}B@X1sZMVRFCj&K9er(GIXx zc8cEA$uA8O`uNB16D$lWN%4`b!dA&69Z}XSr&8mAQIzfE`&A3-6Jv($2xIXkPPx_k|Ukt?SM=|$4Z{B8qmo)68 zr`F>a45v!N8$A^m!knRX#36r5>%9vLP5Jv;H#v*m8KeIC*jqJ2d*$-t_K}Zo%O0{f7q$;c8V|lGH>FLA}1*nZp@buLU9UlK1#Q`cKx6?cPBTei= zcr%)j2Hk-@I8D2lWcRCP-AxB+NGy?Vu#dr+AL;5EA;9MfH{}OLV}c;TDCyURMI4qX z95inZS3I7WB=!n9qchZYDKOHzTDKX)8ATheVu2F42nM%Ysv`xgdFgm~cM_B;4-e+l zzkAP+ko>yPKe4(CCV&RCE#}`lOh$MfFTj-HtI%s&Uj2B9=q~AVDPZR@+k~scr8MJ` z+%pA)9&s#E5+Q_HJ4^T$;i>Wksfq@aA-!*RV}7o-QX;ysxjTAxK}DVIWKNo79XtO-$wsQ%)Kq)hojjoyZ4o+7Rp z9Od=iXujPRF=f%QACbKw8?-vFP~)uX*XuWK+4khSWGLyr$z-w{9> z@Y!i?Ol5!WsV*1&xRyekEtq8y7xzYD`>}DZ!KM9nssee%ubs-m=dk(pQc4*k$ExR0 zonhjzY<}$>gBwn4<_}7=2`p|w$FwC9d%L8CfkEK%=iD?!qit=13P-1dRH3f`jih;2VLtnoid28UQli$p`*ykRvf70B^-FEKf zaqFf`>rr_Uo-J9N|l_qJ$=&Jb~4??RuXlv?K5ri=oEWE-@biYiJewK9aG z3!7v}1l)iw7ROY({aZ;GfZuw@vrFPH-)o#t=}35Z_}jkETjS_)*Pk4^L|;4&zNqf$ zoCEGb?--}vtxv7xlM{{P*2;{!mQ)^r;%~ypH|UVJMhY>w7~Ga=S7gi*je*pc;t zz`+g#V($&Q_GZ{?-7c!sfgMP9$!|ZS<9Zt&Oc{Bq9S07yWpMV#-$litw=>L--gsSsNG~?S=fIGWYwS014=0*&Q?!Ze(@1`@7qpya z9ic#MB(TvStu~Dqbv={H;Y%L%Tb~6Ty9t}z$I(~EQ*u(mcIMw? zS3Kq9M|)XrxXt~csCHA_x48%xk3opf*pa-1#BULSS)vD&cE!DWftiRxvjP_bIJ- zCGpr0g`hNniFLd`QGiFA{8=N5bF7MIQIR!BId1dRA3=&0to26PvMtC!jT9FX zpsPhVF);@n$3ZwEAKRqPwP}9;M@;ep_SE?b!O`}uR-}0$5##Q~zWJONFPFw+F>pM- zuds9eKDKv&1`a8uIh!Z{Yn;sme$qmmp>EX>4`22KZ#{ zWx|@nf&XA)ey5+R;OXBP5WTYg9)76jH^3Ryi*R(G1Yf>gx4GoxF58*&l_MKH8n!+Q zId&8NkL<@SP*un04{s8i7u{6D_K0!T?3QXa<44z z4-vrVrsO%meIc*nT%SFrWo1YB_BQ&3aj>uv)ypKbu8_pipn%q!r1X zmY36u6g<***^2gE8Mt#!dRRSh?F%jbY9=xG3jPczwJo^59FucOt0o% ze;-KMl4pDVX3=9YOvItB_li`yb%7WxG)YgmD6 zNXnLt`}YblV>1)L{|H% z7IfmN={}-qulK`}AS%HPl?o4ZW5ZOV(}ZM=WFlPzqfhZ@>$izMYge2*^C(~!2!IVf zPeGll{fW-CH|}UfL0Ast=`J=Olm2pCP%exf>6a<-O738>1mtE_#dTk$^pKWKv)?QE z-#T+WQ!_D(#mmrB&1eMq{1x#%?m9d(ug_7@}h)GC65Z0%4>X^cU&mE(?uDz!^~c_A3j^vHyH2h5ub zd5TEU%3qOwh7fa1+O3b*a-=LGV-0!j9cU zPVN)zt5YsHdBAq&VdcmrkH)RbY*UV8bGaKQCDaS#u=U^1A0GH?@Ly9M!m7g{@`5u5 zcyV!GemvZ{8*c3;y)lVr@R8nwhx~gl=zWSivsJN@xWh*0t!R-Ccfl*3$uw_wS?!D< zgr}s*y$2c^9bXXcQ6+C}Dx#gjj^mXa?Tymf(Nza4vfAH2jCVhzng9 z3PsD&Q*l^51W7*xR(A_8bFq-MFq%&JnYCd0BcIE~q*s4igJR6)bcRm{$n-Bb+f7vZ zviSAHOFUfNpQz&uL0U-wV~*3v-XMhF^$RYRiJe1}4Nb3wW`{M4IJ8 z!(`Elszh9&Qr5H7=I!5eFO{l)H}_PMeBE)(H2xlvQ}>fG7fs~QsEydH(nTd?a+H*K zMooro405oDFp|j0K&DZ^&1WR`{cHuvAJVQzYiYrB+YC%pttYy&;!*rNAFM9bF-K%x zA+PC+TRL|>dii}gN=knTVi(U+H@pM}Qx!9soY~Z9>V;`3N$R8dnTeNnv4w=C{CIW3 zNLcA0u*aD-olRAiMKVa4*#0m{LHJg+G$R`CDoe>zQzUZgrgAmR31)dCUMZ@Py`@U6 zb9(LgD0wA8hx?U<9sA8w(INamNDNSl7U*k)b~(x8sQUnnt>GQDmjnW;pbF!xPPcgK z8O-K*KyF%AnwTDL@CqRukaDx!Js~Z-&`my{pON3_8RJx>B*z~%0#DYLW{Gm(d?2It zz)M#p*VDbg5ZdUc(k{Zk*@M7yX5SFh4l!^eCI7viR~>C@cDhlRJ=bAVDvF`58{fA% zwpTLkg&>1Qg*hA?I@$C@4zRspLVi~F{VVuB;p;OU&fF~I=Tbg`FCx^&p69>xc)0ah z=CPaVll#2;>PAaWwc36;Upc<4Y-fko&D8}w^%Jq1)Gv)U z-f@2>`wel?bT;D0JqtSwc4Izg>E&5t$!I4YfANnVk@Zv|AqEe{VyDdaAPZJTZJt&} z5bMbEoY-oy5r&FO~ZHO)tU_?2&-AMNbztDw9l$v;l>F_7# z-+-|^f#wopKo#hi6W<+u`2o5x={tJiA^h@xJX%O%HYISt}XrsrmJvU-QT&QXMeru4Kj|?@C1CA2)T2Ne(%TmsHI<6KR&GHH`|xQ1ahtkBSu;m*XrgP(oLgi4WiR zcjY?X?G$ReSwCkyMf;gASbZi+akfH!c)s@DPpB@;?&mM!v;Sdbm+lQ67R)eDZ%{h; z;lEw~g$kaEe*-&Dyb7kI&_Vlal&`EZfgm~L z&ZGS-xvrFIybXiBmJp))LQo=}wV1 zlb`*=r|+~JM|0c<*`%p|411RRWbBi^>PV#Z?zw$h=$9K_8kn?2@a&Dr`;q&c!gBWN z*r)X6`?E(t)rlf&glTtOOFb5V5}^m#$wF?C$%87b(r`u;TrPs|fC)#tyJwJ;SXY*v zYG&GSIZa?omtH2%R;R=d>Bv-`t=+!}5`d(DjnnLKMxD4lJ*(t`{F!bSRteF7%Tial zau6t3N_>%?s{5S@BLZERUab}$BwYqgXv~30k+|xNDTSyzui$xDDi7`n zxY)F-XE8ZR?L^IsiCmPHnXHPwwEEVBQ;w@gr1FZL}9f zd@_<)Hih^ED7-DkI))RCanMI6AM<4qKUszg(QP)a&y+4KmBMfEK1C0|Zjiu;G7`X3 zq$&m+>MqnlG!VT|Xg`|*lvgj_P=-V8V18zOgtK3Dbry`C?IHM_SKa?vf8&L($7Mz_ zgZ;h*c~1m2PBVM(Z(wzw4`}MYE)v;xHP+|R-uH}<=~Dkn7ZYDm^v?2R!XS&O-& zp?RLAMF6tzFU3-^)L$Kz856Br-W$EFS>CjP?v%MuwV@_StN#s~N%7|AS2H3djy-C2tna$| zrh4-|@p%bk5e$dxH|6Ld3sv2H%oCC7b>O+Iw?^^f*U(^pfMLkPsah+)EfMzK;0h-9 z6*Yfj{cqr|Wy8lDzOYD%trlDcK29C?N?|*Dz86c}zWh1OQgccC_WUH|3lWXK*M9WS z(&)S0FjK_ScwQ#rnjI|=Rt;0JqAM<9)MPxrQi^sG#GRDLd0e5vF-$&ZhIisMmY*EeG57zNI@a(%1M zs<+-4$B(uvyoy_#IdS&ACmf%GFhq)|8 zncyy};y`fw!6e74#0%0-TJ^)CmhgZci@n|D3P91Iu7p=)SMw?pJ%R9bq1VH7>dwc@cRkx1Z$_;jQa+tP)D zC`e28v6utur6L>7KjIm?5JIcVNqeZ|qwSQCdgbavkFR z?#&&ZzeZ=-ECw?^!gEp!Pw9AYmhWuIzyl4gm&ro!o5BI8VK;K@~=0Nm^ngFfUT^)1WtIGZQu4pcG8Yb(96fT=1%;S{F=SySTI!+{ilp5MocMbHW zYDKv`RFdEiAzG~Q)}olFn%We5>eUJAN=YpK(k=z}${7R}nt)roddcDQJH7=?M;h(8 z&d;3$?!b{g#IhtHg;?^U!|p?^x;^JTo|M)4j32RZK?Tg5{j(@0V)CV+C2BCcUkERK zTdKgKNqR6xJkZI*CtFCyCuo;6TJ2hvhlu5va}+11U9yxoUyWTd&35owmV1kOWyo*f zL{OL?>H#17bBY>|cq%mQk(g-SE{c%>+jh#BxY~>Dl5DscG9w~TUAZNpTYK2hbMPPv zQvt{B2+;nycepHI&g4()L|M4n@l{gQ`u?k= zg8XjUjeOToB?Nb(DRXk7 z%Dj!{?64f(RB9a5r3S8HNhnI^uL@G3+?gpY>9^@^D^p8(%O#Ct?9WniZJ8{dsgnC# z?P?vSrRW+V-ECfs;%FnW*~^8o)xTEeM94QcKMO6hkiaKy*8YOA7i!&WlYqnbqiNkY zIi2EQ+Ck+<1Zz)0OD%(1gNRl3mPcl)*tQ(eaKpBd;APqfHXPO($pU05=iyFyLU~gh zIc%=RO7}>-BuDN(^nJ&BO2@*J!sMI2)7g|qca`1tADi}noC$ifKoTmpy@=MvD1nr_ zsf*#?6vq(xk-SY#@4U$eL53%o_inkW0{@kji~-bKg-t1oT{A;d}Z?!C2`MmJ|=YAUHq=+ttn{p&AhCZe3p|LW+`Tn`X-gB zmj7X!*41}g>F=G>yQHNzWeH*5_}cytoj;RjU)Ra<3;VxN3ZCkGw=z9bKl|d6Fw&r3X`jgJhe8W zfz)aqc*SYgx4AHpa!>o&nyc!nS7M#9x6aB=bR)G!R(EeKt&ulR3#p%w+uL99QzYp- zWxEcIq@xtHsY_@OJ;lma%8?csG-`xVMhMRUC~39~AY&@z@sw_Vg4VX`h*Zuu9a8eb zO4{?jkW>-ZAOK@2U=YB5vgfr0_fs8nPUDN-+plkU5q|LL1kgiuRv(EmPE$-s@x%yn zDu_5AO*05Jn&K?wHVcI2X`}dIF8sIlu)XK#4L+@r7^M3u9n&wXse3X_fn}S1q;8e4 z@x=F|8&2LDKONCDYzI#p^z8Anm2$E{K9O~$;rF27&e$+DEkl8Oui;8b$L5808{T+H--Pspq8zRGo9UKuAShGugY+l)(^tb(j?&lGE=G(N zwFdK}9Po*>7H!sL;qD9e?JmvVgU!u^Ld3+W`*aPpH>)?c44OqD^e0Spvu>}m zHqM`QJuldrs@HK;N!aBRkzW^HTG8ke5ozqLP6|N@)3f3UtgZ?u=SGgHan=z%Vg&zT z<-k3P)t)W}IuRow`!`{=!a9B3sBDlEf>nHiF@!lS{RVS`A>v5L?3N5il46tqy`s?! z;K$~*$M9T3ZYG6|U>pfzuK3tFCshdltZ-8eOz45(XMANKGHf#5NrV*VCVcre4$0XW z^Te8N`1*nb{IJGruLdJ<;Ye69%CN=e$)00yQ(;nD;><`RT+dZO)u@T^9o6!aRCm&G z4-94i%YT7Xe5YliPrf>Bzb&G%u_-10ExJR158U*_E* zcGVXyFc`AXuV@&ojpjB#CcnUM$#%rA{UGGHuz*%e!ve{xUixg3#NEEYqz|#z8Py^US+btT zrKNq3Zc#iL1?L~z)F%2|cQ`~LS?5DzhNm~Lhxo6Fea|zImXafySKMdKA$NEy-^*sa z82^><#VE|NlF0G#6GcPc*b?Fw%5liLJ$8yAX&A2@GTb*wYs6XtU;Q&hV~suP+&>-3 z;+y3-Se{@m#Y)nWS5JZ8eJdr2)N+Za|LO8F{2&f0PdLjqr97>)$0F=Wk7^7T5703DO#;UGg1XD8 zHjFK_7@38VuL1JDpHaP7nwYzF4BucmsSV+$DpwO4!n)d((Rf0LJtFgM3_;Jwc9>wE z(t&(asSKm@#|X*@s2#N{h6qX8-bCFpI(V|g>X8%vqiN@z8(D!d$dcd~wJdxqj3)r{v zybbrp>${@%@s!uo<8@;~GJf$Kg%aR{6nPDmuQ*a{f+ElUPqG=334;33Z1DQlC;6sd zaO#wneH%OX9+#7BJn}jB!;Uw`uO$tgLV%{yeB|3e3S9~3U@A}2Eg$p_(*F@!Pe+ry zATF%^kuJFC$m9e3)Sw1pG9-!~9h-gSj9E+)rinFiLHUc+j<$iQk+y@I`}g)!wBQ%C z;D=9M4r|e9K&zU|eou;1rwl|!j7o0CZj%(B@2A!cNAA@u%Nwl@R&vr$^C}saYP!d! z)IoA4c)G^#ddVTmqSBIa0MBN2kM=2E3}=Q3r3dBNV|uj-ue(b%yUJqv^rO+FWV++s z`JrcbyL{3*A%|V**7_9FcxvPx5pUhFkI%u4NZ5A7L!AJ`gB1PBH-`~A8YKy%wiSwFqMWq0$-*78 z_2RL&_-~QV_3AQ&4Cn>|Z?)5mN6(T=v=bs(X|zNLJeL2k9qx{6NQ5b0mwi)bcZ6Xe z49yj#0e5nD3C*Xg!?O5twzzC<0BR6Hk5vo~PIomqwzr^c9C_j`dgadq?Q$Q;XlkIr z_XeK4>x#z(c_Ji8s$IIfgxN@N*HFG)?as#Q0Lk6NfHT2tg%uWXR7Oe$9$rczGYJ<-lz1#;sF+lVy(!Ba~9kS|3D;RfYOL z?cBof@AZ<<`j&jxmf&l(SlE$k?T()R=BO9;CgBCYHzJ8@@Q@LBUEU~5_dV>6fD~k7 zsC9Hm=)374(F*4eUtm2Zuf;NtppTP-1@92;ts~N8B{%NE*e3Fk1|S4kqbXW`W^sP> zxh}J?NXFe5lM6wKEl%dv9Ks?;4ag>_%=*X$eiojG#r7di(Uj?1TPq-;^qV^#@!F6e zr>v4a9a$o(<vNFNp>JM?2nG>oPSsp}q%`ss3$si0i+vUE1Kcz$ zf=aCJ@ok+FG+CO|J1wZvymnK^W$3Zaf#`G_qA8%Z;b!C4(_}8 zr@q|SL}%R4K72^XnH)a8d?PJ8-qP#A z8Ipb`pJq&83{AVg`2lf6<(i6IWh@j=EPsKHG;s{~g*^F%l;nZM#|CvDbcHhx`8bq) zWlQ9I*973;ixc+vCGch)4w-H z?AUe3m|u4HkBT^|n4c@l&$sKDZFaeDbEQ~xOR^sQJ-A~LoWhF~@wL!JZ|*v{)@4N7 zn_ISFJKU7n^rIcfGwI3fSn?a4z%$B@HfQ<)O>4Xo-M$P?3e^VioEb`W7&9%;RH@QU z&fD-7RIX8mLMk${XkZ}Nyq!(1qeKsQ!;L@WLrlz*8f1Fa{E#ed2t(V#&c=!$+OQq;VtETq zcarADV4q0eA|&xk9zT{xqe#gUM6?KoILFdE@(I>&;o^o;`E}ZJfssc5POrc!mW?x) zw#a9jMPdq4YMOonz4AV0oH8kl_jLWXL`6w+1hU~0=lw%(Ka2X>RGd5HTow3cNKNKu;d?!*If)?1RgE==)@>^}dBS#P zx^m>DN8_Dm;m2-rPwv~;x5iF-STFsf{eDIFd+kZiV&6Gc@DZ4QjJ29L`+6E+b!F3w z>)|514>isXzqkB$bp6+2blj$?{aZlnd;CnMmy-Yf@k2w*CnEoRdDx?2$3_BwOxbP; zI@kH7cpoFKCw-wf_Nc<>ba~9v@QH}L163P7962V`Xm;fpoCUlEQkd6!^rvs}>=y2P z7YY5H*+$gcmnl|~WYM|+h1Is$G%68!gf&my&C?Kagr6@(qh;qr#2*(vA})7xcyqP; z$Y7;;W?{0-(L*1Ojvc@Kxz_H7L&;C@DJd(D0GUegae!AH|3-k6@eS0L?$Hypg9nMm zWYWbP-R>5}gD7d7=7x5c1A8bXm$?4r4|}(@VAqzDSyo}}a}zAvg28I{9sTK3U`L_w zhejowXa}daOT!QN`1ES6k8_Fc#=N1nPTfTL{qMiIN-W<*Hdygs;Rlq<2X^G_O_tzM z>Y4zT0OFG49TO2ts3S+^Wo1-;3TgKF3# zV4u}^VA-8gJf8z+v%ioneR+n)pZo6L56*;VwRLicg};G$T(T^{kAz;60wx~FyXjFxY+!CC~1Gq zd~{+&CsBg?8jn7NZoD>ASXk@U7+w z3~Jt1^B%2uq$&Z|MlJvLx&V%Lwt-^f`=vRRW}P<+Y-N*EPZlaEcktGaNWQJ4h=H7r zK)UeLz9d#LI;G4Ro#&5>MW=M-C)-b$E|hX6-^cUW=bXP|C#}>xr5%i~iQV6T)GaHJ zIo{?PFR&RM{G95NaoGMy5K{VBgq9MD9)o3%BshKj9=mD#Z7Xi|%TGJO*-(-DaN1k_ zj^6-xGAsR)wHr}9GIIJruG=_TM(WBvQF%ST8v{4ssilQ%PiA7TpYY7zd;R`OFlMmeSAa+EN--T?D2ukU264`(ZGPi+H%Up z%bLBE^xPc)U+D z;wow|fRP>V8!KJ%YD7zd)`vBap;%_Pnki$&wD0Ydbl!RI^32P8xtQa#rN<&}xu@7} zdk0e}@wCSf66Y)$wU)HER^AnVnI66Mbtwx{qS>GyfyWi1r$g)rA_1hffgGn+NjB0=AUJZvkT~7* zu1bd44*C=e`i!#|sX%HS>A&*;z1sJNw8QKkkwm8`Va8Gww_{7OV*aY=oeg-BCC5O0 zPbwcGFw4luaEx%HCF$dX7|0~^HJ15)1&upvAEwtn-xqKohmILbc5drY?pusuXW2I3 z-5WpngHHCSD~hEeDJ=O+OQ@=QI0^0;rxE>xR$U~*kcRl;d?6`^a0#UQyujzmyA=#e z+IjXdhDaK~wb!~UkvZfqaor741W3%+YQBtEaH^I}i_k3LfE`s}_>q_E4cl{fVdWlP z^gZ!$)#mc|&=I}${;xOm>SiNj6-_L5$>u)chm|;TeTLd3Kd9~*ysB$ic`<+?C`H!^H)temKJ zMnE2e`FQrvE|Gshr1?g(*&ELYjX(ZP0GZIdiR`DC1Movzo$Q?~2kRUT(Ad8Sq3jTn#^_ehRG#Z*QL`okbqjQlVyOOEZGFWU=X6Ls{7U@TU`dyl zJI(xQD(1K-kkdX0NXC`~1E!Rqw-lDl-`6@lxt(xFH#bAsjp^N?_n@zG>MA#d+GM-` zK!CP(iSJu*;HgsM-6%*L({;G}xj-{qQ$_h6lhG`3QB&m5{q{C_DHC8L-E{ZNyJ0B- z{#BXGr{-2JA8joy9Ar0JJ3W3(QpsXqu+6+rhyTzsuzp3jmJ?~(r1w13|Da_O;QyUe z^&182rb|t_IcoTo*tBkRM18d9rqP@7rrVO9yESx^nhyWHzoscTFWA+=Si{x)*55gI zIyi_wd(1nI6m@IKg_57itFONXuv10r|F??=Kbp3>#?jyR-;NXY$Aj_IjJG|9?l(>= zys(&h{9ONsN3KYB>DRCN`-OEJh5@(UX@iC9#nxYl-hB^j?HqId%{4MX! z*pz0qvU#hgy^B`L!z=pl{*ID&1L=k&T)g(HeERS>h`>dXlHVTsb8$wT`m_c%`fl;h zWjPMc9-o=RZ9Rt+b>BQ@<%AFMWVdv-?b~!2F%s+YjGb;x#-o708)8flzS19 z;%(20HOjf%em=;;{oDl9%97S$H%YQ2gl99Qxd>u5=gBK*-frtW-`NPHz;Pf9c5gKI z)rV8lYlKh6j)cc)?(Lh~wCOhiGq9}L})%(kwg_`NoKb9N}gs26x4Dc&VlK{*~8s10&Ze9`B#vN&vP->rVI zD=sok5h`2^;~H8T$k#Tol6J(@-#9C>*AO)N{8Xg^fi5)k)Q6L6O!XvDqc%OVK%>Kc zeWGirAC-<>6f+@v2yF0JZ{pLX7td!Y8H_LpI^b*bIs*%W#KWvD&X(mfqRsEoT& z$P210gkUHYZnP}fnRfqnxGsmajZu%-{s=95Om)d z(ppL@JEQvk&r$p$fAgu0xli6z8ejD~kaS|V5>2mSkV*X<7sW16h^GlPNbEBgo2JqW z!p41Tt4S9?7lEqJKy}8O)0)3}ecZ5k4Dp@G8BTh5tg@uw0g;_&T=?LJ*h1f$ZOm0X zJaRY*J)oZ559?DFVW{57u6Ce8BNB{HN*Ir>RkkEK^-pr5QuA|rSnmNXe_?dp3<5EUt@Y zIBl?WBebJeo)SH@(lc1NRZCeb&;UlnY0H&M0&PrH?d)r|2gc@oef>SjBpbgr|4MAC z5>(g31)TZKxTcr7i({sq`YES(j~I!weXA)<{2*JBp=g93=tnT&DLBIYXUuW)n^>~5 z7toX8t`(b}ws0gidJPh!&eXuhsuKk7b~Kc)p9B@kXg`#~DG^|JC&REfTq+H4XKC>4 zu@BCb{v0k_!83Wx{_=*GzC8`w)NZaPJ4{o$8!FHM=t6dqR+sf-&wi8lML0Jr=Y)(@ zv<7~>0xuTEUuqdnTrybzu>9eqY0B(CLb zy0O9Cn0CpX)+?c%2X2=3Fm)z&Q7sm5T!%O^5mF+X)n!6~6cMfh$V^#^XNYMEJr|J0h~MyqBi4Ic22MmPSfqj>Tx>}SZnnUhJ7g`eI*V$ z?#M^pG2eJs2s4ok~wV;1U;i zp%}_*Y+=O>C<>A_E0eFAAn(WwrkrIW&PunctJb)?P8@vRd&z(KryTEe7}~+PM057g z{wSYL&&k_=j!@+*T%VM=|MqMS;B)=zvBy<*Qo46!$WtOJaCk^XUQMFV>=P0KwL@4C zV2!~kMQ%0JK{fiK^#UC6L4G!Moq3y_ z{V`o}(hXIz-;HO7cBP@$LOw7Of!bo`eP4BGp1jy_SgIX1?KQpld?TI|1FpwTSVi=m zamI)4h1~MNBixmF+YGwcp18HBuV1@}o08$wesI}h;<#&Ja4n2ALe&OL8}Dm@iwTe_ za%Btrx%I+DaI=h|7ha6`+PRyFK1APocnn+yAROn4bK#1lHsj*92?(83rZmsA>YMA3 zi**q2bTeifxUZjaar}3HKZmbn?8-s!tKLpB`~?8BTWbcWlyB{_D%rEGxr`(Y+9_zp zvk!;rk-K#8TJm-ckn#o{^PXvmXpIIni8P*MEXqJ!25Ax&8s>s-sf2*w)~PYOY|!0` zFnj2;(o-T6ZX-jP_#!v)eZ(>=2*OES4dZXfj90DkGfB4EJ39rXLByRV`&gx8Uk5(VoPALKvJ-;#f@-4xV4;Int> z{F&yv--EcwZty*ECS?kuD1|~Qo|pV5rQnK$r#iF)g)B@+^>^$m#!cM3;N0joOt4xS zeBKKT+cc&ooTX@#cFz6y$$jf1Cm&CEo%z#lNPA9@QDhRw`o4-?mj+#Lb^gnC6Z%MGrS!&~;P1ivMAkN0q)zA?ZkHnC3WEst$AFh;G@HGwVcvhA%4(yfi<)c;c`8}|4H9ymTP$>Q}y_A@+9E~KV zOJ3@;w4Hx^YL{ONtobAG`q%qK23vq@do93f0PAPbR=;{PRz0z3Ns^^Sd&u1CD808Q z>e~Eo4cfY3sSn1y-Rab+CVTxsT~M8hMq90wgS?^j-d2pWjau*eor!zTAs_FO9`Dd8 zKj3He>T34vNtL|xnhp`?zBRP#JU8MQN|GIf8Rxh?PlJtNg%lzsg6&b17r>2p5-LRf z*>*84Cu2|j{_f;@m-YT8IQ1AaUI&BScjDjA`s2&0bQAkpy3a^CJmqWFdqSkV?%rT% z9N6Y77yY#pR_|U!Zf*JUENZmP@XEELwi9wbzW~~zzKXoP8*ALuhCLnuso^$X`QsoF zYa9Ssdc&Owg-Tf*4TfyVx8QUCdqMj9uR(lw(WT1?m;5%JC3C$$Tj%Z3v4^Yhd+&u8zfO3kaxR4?$f4;e_q7;-J!eGN1u~EWj?DI z+06HR+~T!-!$;OSEU5Q{!%@rC@cLZDWv4GT%b(rfntnqI!oGvoUHho{c37+FiW|DfBZp?(2Rh zyUiVTlsnJwh3rnE-qG!+PDUH9XZUk9z^w}m-E)9YhA^u-u4Wno)2)o#?|yA)09)q@}X*E z|2%?-0x`*3b}mn-hih3=f7Vmn59BjQq2(X%)&Uu#%^&jlpd;OJy|APV`yRuQ^EPvj z(Ia4U8Ut2jnXq4mlyPSfR>GwUVCIyJfU!weMJ*1FeFsBQ#3T^=P~!WI_Rmhfe>b^N zv~i0`WdeIM;KJ($8u){B4VtnkZi~{v=RNE1bN&_A0Ns7I=8e?~(K$wOmL0-E8~8MK zaBA6@o;sToE<#T9)w>@=Z#X8-n9YJ(rFMeMvUVRCL^i;@XPTI~>mm7liOm;8{l)yP zXQ{gtl`P9{zd3xTIC0Xu3f7o}Szk=SxXRcJhrudjufv2Cy+g^6BjRiorf-pKQ00&z zAr1%5hGDpG&HcohiqLVjo(*(Dh2E8KVwr=ua_<$!* z=^N`R*EG_b+)d?gw>2i1nQzKsE#a+pH#VU#8(<>|5KJtJ1Zy@^4$d5|>~IUs-0iXh z34+v;H}!|r8=K%$d@;J(9Fj|~RII<9peucI*T7XRk_0?mCPsf*-Z!@_TLr@_q>#rf zHRue`xqS88x}k)c`@HLBU?DJ7h=K%A2I5s^j}toisOB?O11rg^sQs7~rph`MJu!^$ z1eYpd^@N|m-V{HJv!uxKg2qh;hH11C5CF&(GoQ-?jcgpukWx*SkjNqj$HSI3#JPo< zJ8s}2-5h3oJjG=<^q-K>0D3T=OX8|v#&kd~A52Q0rNF)kg4x79w)gfoebAk01ACYU zJtg|=b|m^=$l(ohM#p9$3SkWi{xTf3h6A#DR5rP;UR%n@$B;4^KZB8p~EJrL1*8qah}&* z2OudjG}r>?OA8C@GukQ>G3Zr7-+8XthdjKQZM-&8@vH$~GLJ%P*7UumZ ze;S*f>L^e&b4z(gdaXZEK=K&7bA@{jCi}E95!?{P_Pb*@zRj>0IhBuutq*Ig`#c5CuHS|y$9U>e5k%IEJ=`B{J9JqKE8Vcc95WFhm!1k?pL~RP ze0j0|!vV&j8EtAEs&Gwx`M`Kb&R>;yd$mh{Ro{`5e;~n{BnJ8TM=bb}+?nLuaMypO4;(SJ?t^LD&y-b*|fP-8#);l2@UKDVatr7LNUF#U=Y}a~WaZhq` zIOytyzdh6`6F@bIx7avM!;OD0Qi_=SGsLjqTxSZJ#!ml%S$! z%I)>Gv!yfJE~QRnv-85b&sIX)YV7Fk-K@+sWAJ$qKZ)lfiQb|;EGb0-YpBFjqI39G zBM|b1$4uREDMft5Xub^E)FQn0)rIgR9kD#J6thABymdu!KWBj{#JJTmlw$?He?6b6 ze5M}tK1|^_5;w|d%O+yQb?_#NK5*nfsuf+!LJ4wngtDXpS};Dp*Ia{X!@L#cl}TjC zOl5ECXWsC0Vki0_L;FnD^CdYxDFKp~L}}zWbT=o;n0(_TE;0sC*xcM%YnS8cRWyW5u zR2MS{Rge$j*%<&*nBjp_u?fXZ_SMwJByvC1KFI`2OXPwP-de`0Dj_j+c8$(>eEI8+ zRG0(IvOYGsKGp1@7pO~qN24^za2EoBK)RuH+>~Lo1NKyoJDNsF<4uC@Jh|7BLe*5g zKZ7QoIH+BilO$^jo~Lf(7U_nV7y!XZmSPfN+r;-O8zBs&B6@15Ow|EmS0##NE1`~V zJ!64=&*+=1*B`6BBe`-s1Eq*Yoh-0)mS4c&o$FoVGUHVax0+KOOu@{dMW}@{P%kf@ zxK}#+Oer!*i@SDvM!Io?^6{zRp~ZpD0Vl8(r+t`By>AR9pf^q=+L1O1?a@z>5D=Z6H1|jEbZU$?_4_3x!@{Rr*v%CyJPI5YD!YC{`(Ou;X}r zW7@4xc7oE8{ie$92oNPRa@wcanZ7>DYj@Xs?EBL8(ASZncwlPZiz(azG|@+uY{J7l zgq+dW#DufTwwQQJb>6kdU>lvNBZ}h`|2U?7=M{uRyqtlFi%Ab=5sl|l0Xd98|Jw<& zisXo_#)XDh8Tt^8w5j@yl9(H(T1z^T=OlxN_AM}wpEg_z5kJTgk%5M3=I{B}`IV1V z|FGJ+V7ej5y^aC`g3`UWWKw%}4V4d<2>AV2rK#if9+4uZTe)RA^#+tSnwP4&S@v~; zlt9dQ!}cX9#wrzYgCw4>5Lqd`@ktriwidy;puTi z3nZmtdPz3(evOb+%SFYd3qYg-L`*?oZx9wGwztIpx^yBxVKAR7p~4~@j?307r_vAr z2;cu`h_e0_Uw{Zf$Q{j-lTS=G=!t2ktQH3~TAR8+vUHh*0%f%?u1H7qKTW=$Z0w1w-K@9E zzO3!$*Ck<`MgCQJvr(d;eGdI$zOyYtoRD$pyx_EK^;@;ZsLNhQLY`W=!V*R`ea2tj ztp!t>-=L#rY5fwTXH8zK8D!(!w>P%s6sgSgb!Kc%w?PF^>vSZcXU*YM* z8+2}1<1YY}TvBYGzIz9cLbh)}X;p@kD`9AU5CRw&t0g%-N5tyvEh4>8EEZ)F8XddU z(iO{|f}87$sg3xMuNo`GJ=Yli*(OZu0nZCh)V2-5a8@)9=ZD1qQ4iHwsnlpULZ%Tho0pE+!b5IB&tqqGDhTThRDJR<6?(O1-YX_D1ryG=u9=JxdYKU;zh26H%d=zTLD8W6fzzx zktk2x%MS#67W#NtC>BAFdc*t(R7+!vtK_^-KP>1B_4n+vAKkfACN>Y|#Mgeo=?m!v zdAovgFl!WEcE@p8v29ckxVg_k)#f2RXL}Y?dLPuk3P`5~wIIO#B$|8-KHk1pzO6^5 zpm$VJL03J(DnbBE`2;z5K;WRsHaOBqo+V~hXzh2YgYOxlk@C&TJ=(T4xdM&c8T(gd z8pA@o_=d^erW@wGSNp1QTZ@v@uf1qHvie-Omn!V*Sfd_kJuw6ZOFJ)L->?cz5G@|&C;I;3ox(3gFpF##54NN%bST_n$R zy}RL@5gRfCxtMzLqbfk!T$*aIZ{@fw|@Q2 zc73#aJ}~~~)Ce^v%i8N^s&@h^0Vaj>nJKdVZ;>Ra2xY?AM@pRA#Vx5$k8+@We;0JJ zd3WEy){Y%*kf_vy_LBGvumr@P* zD;N;AlnP8ukTJTOa9xxY)5wgukiGQC7{$xWLskeP+U#aFI#N>3J#*X<34kPcp&v-j zMv6Y{#yQ!Mx#}?vjp!L_P}n_Ezc?5+P-2a`3z>~9oU67Z04(YA?Cr&IRVsaD+G3&m z6RsZv2#6JQ;e5aLA*ZH0&C4DiCBgz=E`mrkY;aEwQ^MxU?%OZWHHX9+^ zFn=>7{>_%8QmcqOcct~o>=p4l^FnAS)@ zaBsu&$6;`m9(jR1b$zA$wgugxRF?u0(!dUjb*^xfHAAT5wmlnm^c)Q0-ASW zyS>AmN6s2*yPV@I<#usofEJ*p%9;*LG~Rr)l1lZEp=L77;)cjrOJtcm06^fFn};QQ zAh;>uI*r;SB>L)=X3!=vjwzNR$yEkq8qb{xoD*eh<{cFa^1F5aaF{={+W%e_ewa7n z@te6z^y8Oa3z3J_7cqs>1QR$b(Hfg41@yj|d1z+20!I*=``25a+{ zJw72vi|q6DH*5Z2DaW+)F4719{zxmi2zOVwlZTh75ka zOHSZtg3LZlKR6F%25jBw20Zns^Dx12Pj3rB(uu9Vz<{ZRw>pcdVa_+9r?&d5DLXWg ziLZ88^~DJh!(R4xBVc!pQLR2@IM4Mi-dv{)?TK!MV|;4*PD|tJqOu-mF|!~uviT_U z_IK?5wgH|P7Sq=$uQ5c!)8g`beHCT&{9kQbh>23nxuwDz;oe8xmC^CHjuUGzom6>+ zIGg>^D2-1efem`{h_Yv2Q5KKm-tdhkAv}9rtLt=a6 zJ1T^)SGBAh0UDT@iDP56a7S4KDE)bojP`)n6tctYhUwaU;~wLUOGEhwrh6cP(*9m`6Fj&q|SB zexs)S0yr-5yf2^4a`MC7{jQ;H70U4xSrn)em`qi!QvjZ6JuNZ6?(^5zXOX1RH>k}s zU2_r;1F}>n%XHFiOvKF4r)+I}UWfCT6N_huq=SoNa7-2Nf`!7_{*Mnf?Wr8ah-GJ} zH^NIqc7POTj*!LkwBvY*pdF2@6zLvlmzk7Zhhgq6^12t6d`M!D7?xbS}2l|nsV%jGHRwBENe1b{i+`hAAB>`>@UkLdNApo`K7<-o3ZGuiW4l{;YCgo7m*~l7iTzo=0}mWKMCERv8^Tff_N>O(L2 za_G&i+FEfJqXIQpmfF?GY_ll;^lRFmu{<0CZD8 zoVR7OxOZr59!No7z<`b7K;k%^{WM}7JEtHm#m;0$q5Lo@kw|1)mP679T_!SG25F%_ z%~>)s7YP!Sy;rT6)7^OvxxU6{v7DZD$6uHJKE3Wc>G6oKl2lsk;_D>SpBPOBfQCNB z&vNOEcCTlrIltnz)%kadW6EFZy#H$ToBbL2nwx!j=z=VUM#%XbMs+Tn&;8AIEBAUe z@i>t3VohQUIMw*M>w1~LEl3R^1uj9MSb{$6cs23Y!je=B%DGhBH^h8hmSoz;wzLM4 zys*tFLTpj^1QMFNwft}LMcpWkdosCZ-u#qI5;N-WQc6*#nB@A%13jm{L((q40A>o6 zR4OZQKCx+3RzPLC}seh$g11SDC@uO8m?y1PHyAp7X4q6Dpm!C@8PFiwD(CmbNf_h zO^#1e2wC7fqH2iqaE;zf;9r!0;x6da-Ve>Il7G?2{{V20nQ(6B>s@Q#T72uanKcS; zO#$&y2Rr}&D_)*84Pc`+8M{LNQ*mWN&OG{E06t=g4>0^E`5*aNBb$S)KYU9YIX>5b z-n#Zw$HbJkSsInP`i&zz#$Qj5(9H5icehXSzG=e007@zciqf6wKJW4kL(m*#4sO44 zsRqcjE8aY~yVubKqFsJ*qK6iwc4coo**LKS!+HE;uV2poyK zC==M-#g5Q6E<}20FRu_RH!>QU`jz4ny`*(!#7QI!w)}|&pu!QbDaO!nmp46eAK{*e zj?u`gFtuv&9#~J}B3vX=?|RYZ1?`c$^sw*)jhw@1<3>$!hXIPQA`^M9@3J5)LfNla zoTQ!+aKxJ;G}k3qFDM8{`CE=qIWw*!FYS0ct-*CF&O5UG(Q5=G?76ko){2rX)|U1S zHr2lV%{KyK`XqeRzPRcSU=@lk@~Es=~q8m98rA;Q;E-As>;h^C&vs6TyNN~ zlAb-oO|0;Fk$QD^#{ymwbufF^Lc_D6hxQ>zEj7ScF4$gpz5lF$|Y3Y5loWgL^H-!?|F4F#~foJB@O?@TK# z=H+!0C^06uZn(yP369vogI7iN6)Ndz&n$YWq_kD_t^>in&1o^^L@SB5%F@_KSAaL9 zbJK4Oi(deDZFlt}^k)nV%OCK$B47C23vf>&$2VOulAFZWfK)yY#JbSR$Q(=YX*W-M$) zr1H|~Jo%WV3n$?zypiumdZR})#M*bXlh3LARjHh)91qC3dV`-8@1fpb6kVQ1(IEM0 z&pUc>{AQA$a_<(~-RJq?Q%Bp}PlWR0Ku>R2Jn_9I$eM{Fji?F)4I1$KY8I&7D;Tfw zu?m}#bRGDn0l|U8k=8w$g_t$$%vew|oY@wy1+ozg&q8irWtR`6?s_F~xciWiwv_Y( zeNP5Q9-lhyg2voFy`R#@(6~t@g~-5$K2Dk|->In+ZS{=w9gNXv?Ru)B>r|%(dNM{? z)OZbrN|c357N?t^Zo0UrnIix7`~W4VS11i(?3s3E(5w#Up98PKVA`Z> zrl&ifL&Rc1lV%mqiX#hVP$0);$twzm7tfj0CW;@KVhjQhMjY@s5YRFt?FScmJOxA6{@W9x);WwPnd{ABp#zANu*Zqq{vbg3 zp&K{o&Yr~BH`!C(PZ<0Y-l%YGNJDwI?V0%g<7YBH2W-&$N4cDT%l&NMuwm`x&uF1{ zq5m*=-oLKw(gMIvevpW-M~?nX0S^H||C9p$)!1tkKLLDkw>-IlV#k>MEd@O2*A(z4 zucMpyZEYD@KS6%#)?2$rvZ?|f#XU^w-{RJ?$rCdfnV6R%orojK(wtJ-F&;_~G znKR=|s)e}Xg#x)E%A!T(s=&Clg2|3o^@b+-Fs+n^v??TpK&56iI=3BXbF=)y7)`i6 z;y7rC`XQ4xxE6>)z0jkTHlShY{0Jz?LhafiPh*9dHzB5QdnJ%k7oaEyhy1A&?bn2W zSX7pInAh9+_r)?0JHF@V!a;s!Y+K<1SduHY@AEa5goRIcTHz$5o#AI7g16LvMyp;6eOoYxj13kkx_?Axw7jJ$|?}J zw-BsQ&r&wWL1OH-BT+o}ecVbnhMT%wdiT+i!|@AW+0jB=8k@5)8$cp;HV((&+%ypu zzW_Ax)Fd>)GUNY`Kgt(CI!4~nr*vFq-W@&9@54R%TdrMs{tJM+;&J&#f1umCbMKR3 zz%RuH8##V}4$=2*U$d_)*KH{e|Dtx{vD;Cr`A<9L#=lpVjAFqP14N3a!O4Gb`or-E za;$1GCf?TQ7r@Aoa}OTR>(z)D4}E`QpRz4~RNZ%a4dsG9la^sOUjKJcxp zZ!RA_lX|;tlgB&-?($sJ>i@FsppY!gFKt`pXKVlY17DxmmyTryk6$=uwYXM|ySL8s zAMKu+8b4_u^)J`C(tL>@_T|Fw-%#UAuTR30n?FCdf74vuw7B~im!EAtdgsgK*ZC8I zXFu!21bOTixSe#TC<<-c=^4vPDbqh%rIMYgocZct^@e+~ubQ6eZCP(D=l8Zv%EUtj z{w7NaZmONg4(HxC7S$F>7WS$gG@4IrGxWbn#fKc^OE9%Rzx~b=xJ!sXKICZ+igx#y5FSyW!I4<|EtAM<__Bzvl~9BYDJ#) zdg0(C$gfJCT+Qkbcxp{q*V6Do*?F6>=embMQA4Tj0sMvyfDg(^_O5af=`m5e4+z|D z-TV-t>QBNSc?=Vr`0Szf;nRW9!1!A$__*iRayj#ELI;JJ%fKzAH*0V?ey_i-=@gbw zoRo_!qp7X*p8<&s@dH?--@2$3eXYi3*<@6FA3xjs;TdQ-)e5zOepc(JoLL4sJBa=e@_S6FIgIX-hR`#kbh4{gIii}-~9y;BBDs840sdUskg7@<#G)i zux(74>*-jezA6f;mUa7T!NE1uvoX%rF@Bg5LY$e38c^ecnCtrJy%HhR zT@nusN|e=ri4maIy>lmT{&qUX0QlSKoOSRiU0nnx`5{>;L;mSX13^h(J@?%{-jQ#~+D_t9Q=(0+) zw2ao$pnaTk%1famlH6!_fPsH>m|)Mf`kT#<@tdzL@$4QbXk34UahU8L49(+5;F9O& zWoeY<;jzb^cvX;goJnta_QbM{N<-ANs0(2H+jz;k?IU;g+DQg-|b!?Y-+ z3guXJRe1}^UjTu56Dx|8GJ7!vyq`mUioACI4$uU-U-~9GCJYm1K)YnNROBaUoPpz} z;DnGiUNq1GkyRVkd=L59Ki1pO7Z1D`W@l+2*uc`RYE_%g&>`Ii%jCckwFgoc8Z6e| z6HxAv0$BD~ zhiebpCP1f5o$8TEU)Gg-BAd3Hcy(*ZzgWL(wH8nFxRNsFrhjggl8+oT5N_z*GNcoZ zkHzWBDv9PdYYl3Pi;(V`Fc}#icg~6n&CuidfL~(r!W#ec009sM-Pd(L26|n%>leV` zf#pD!@wP~((K+IQ@WwYf^663Hy0yF0UCUDP&`ydW9WLv^txT$A_UomH6=3(tsIF(Fc1C`YzlQFJ-{=N)Q=$q)HWXU^5LUmUFV zdhPu5HCU!)0i~I6+OrBiPK`R<@BDp&LQbhH!%wT!JlSOU)&JKC>gXfEg*qzJI zm4W*;>Z!r!lE>stz-Su&Kd*&E?8zXZc+ZKY*7?RxvX(^ozQj>WO=Onlgl9(uZJ z*eTf?z}GWJp7Q6DQ+MZfTRI}8-3n#5{Qju4-@1}1rN8QaV~yFXbPXsZjz=oaB!h-b zG=UCHBsMPAfS=oGeC689x#gY0XP1Tcc4MPV)bgTsYJaNpdFM9#-Z zo&87ERdXIgw#(9)-XtO4{Wq4ECKDk+ z1id*~@_1ascEBNnQNg6gs^R01Gq_}HZUe@J?WHF}RqHWPX$Ed9N|HitgBAi$oq**{fOPt^)WrEOpQi3V0M@x#5vBs{2L-QB27=jeC-Du5elSZ3&J^J)z z{`a{lVr(PN`yI||8#Fv5t%!8a;S4Su$Yh29ospCd5B=P$M~_OCv;}(<)gw9L?P}Rk z6RN9qJ3hFbeQ{yuy@+$|4?QA>EnV&uNkTqGVPzL9{Bd?}_ z7n5j5Q-Y~-78H34&huEd@VNsLj0o*VQ5lPaiJ)W{u8=Q8SZp zp%40&>ST6)#%}idbnetIfTLsI9>CLQI)2J_3&mvP$hrylx{L1n+Mh?>dD=1&_}jna ziAWMs&hcGju?qR+qW~Zdi`ZoBOe~jX;&; zxHlu~Ej}SqRgmTBN$kS;z766v?9^b_uN!Xj?L6-;&v%A?eEEO<51*nkQnPcS|H@2H zR~d}MW+Pe%@Kewq_CL0YYI{_xMLZI|>_HkO|& z{22c22Y+3HU(kjJtk;Vd%+FEQXI>jw`I6q^p09w;myHzw7=9 z=NI7_h}{7aP9wmf7+kv)h$<0;0-;07c#3@_v_#E$Yd`{p%E$1N zt1Ctd_MS2;dECzo25pCAvN8#rr5rj4lwBTdi0H{*iuL!UTN@j!#rPud?mg57u)IF8 z4G2M(DBFcATPoxi5HD#aQ@I2TPyB?)(h==&TwC14=gq;IzumGniP%WQ;hDoXL*82G zTy5+gUG?j_@q7#Lox|1lwJ*>+AH7}$bU~oWVhrjTCXrhA@B}X%fVN3|SaBir zUc`g;hnFLVqo3w{nNVM?bN%3U{>A@VU0id_Bm^XU90MpcI zPh;g>+C<7$x&xI!b&$q_3Jwh_x^IJlM5!iPc)2`53vFzrDmpq)p}I{M=IMZqi6;)c zYfty>7m#9^XJBSIBNVp222?TZEF;;#H1p;ym)}+O$ysPETnOzY}At^~uqw z*Z#w1HKgw7k%6Gi+e6bgu_#eTq?94<0&B2ybg#YfNF%5*!#;?)D;TC_0F$Tkczrlr z8`UY{7%z#<(fN|_X`wY}LX|$F3_5f?G14`&D9x=po^9?E+9LdtM z(dWj}XNaMGhby_3iKZ}^bYIM8K#sUo#y)wE!>fAn_e7t*ue_iY*Je+r*~jMS=F#dC zgv7k#vp-L9yGgAHH27!|Gb{)1G0iT@A`_6a$G2@MrN)O0OLwC`(Kh=w*N|VDdl8hHsjTNtO-U?lx}ywh`}>sJT^M_eX8MY+EVd*yVYCjdgnoFHCsafWa*caT zzO-U@Tq|}RfND(Yo7L`y?V7;i#pKIv(IhkZ3h9NaC6Qu6@77J%8;)~<9HKrrwxdu% zk~ecf=4k*`7aIrY)^ABnDuo%WJFu3gwZeNBP01Wnu z=>O~ps4WvDHzom_3SC0=Bq@Yr*y}okdd_6;t8Y5;?DxfEMgC+-%&j7oDb0qYrQ03{ z&v|ba*1n?~wY}+r23w@0%1FIc_#-*gK{Ei#tRP& zgn<)rSw?0>1NRdj!%Zymo_T@fG4lE_tL^*7lUfrQ~&zaMB7?CE&KX~{8?HVljU_)=Fs?i zCQz_|d}wS<{g`mxt|(Z+yhJ@iA|oCm-D4)vc;n_SZ_5y-!|SIw9(u7vao~|T3aHH5 zs?i!N-$1))7JtYw#jIeY8jP%kA>#m?6dg_?bJ?3x3Nw}Poh|e{36MuCgVQ-5i0~e} ztNfTO$4Wl%dQN5Q5I9si_s*ldDrs*j%1m)2j&g4cx8=yuP_sfr!&QiTRPNllwe8+k znwgcAmYS87m6o>7pU!#Dc{}epzjyq-`F!BHp8E!TZl3$P?(g-zt_z$f;saMicc9Jp z@r_zB-O^qg%IAJlmX53Za$YP>(EqwG-N2e3STc}FJ??*{XNvbYm+xQmneHb~(}7{< z3U@6OBVmO{nm-+MOEUDiC3hR`r<_I9mQ%@M9>NSYb?vuVke@MsB+lQxEGoMfyiscB zGNj>e2q1gDDf)X8!WB$V1d^qU8iCdo z=Cp}Z`@`havk`+$B%7uG@TM zZHUQ2G--;m*)Qp?{N`+JX#D1dL=`=>J+xzbkiWrPbVhLyh1c|kGdum5e)N1+ff<-f zY{r{+*^QcdUmcXJnWAY0lY;rq^ zUkqz6xbfO}Y$zRt&Mh{DT@kYc@B)8Wr@>NQ1sXAYu^!C(9w2<5I@(YAw(sY(8*2aj zjg>$Gyf8eIz%GILa#g-H;Aqv?la&<@#g1j}%52#uog;xz%uE&ZphqZLw_P4F5dr&q z=H-e~? zqRp=GH5}%zLbcL~u$eR;WP+zuTr)&{rS0lnkp&J03VB-Yy2LcdYMClz8Qkrj*)Ja9 z3)Vq;BPqScGuhdcI9y*oIo0xJ@lF||B9eRlRWDam1h|`?xdtbG_@DNAt`7O?>8ds7>_HKE0J+x4GZKq@%1xwk~`D z9)J76MX`2p<6C~;sPDxQ{D!FhTbx<5g8tKVY^)i&Hl=k@61YR^tCJr5hv_0D?zlIc zv7tqPq@c=pH+43z%0g1R=EVU49G8k*@VtKZzizq8CTPFFC;i*acwmPKN)s9DbhhkQjVJ)TyR_#( z7ob$~qwgo8lH}c^^zT)q`*&Vec)qrC3f=d1qd+>tKiI-QV29lIlQO@0^pXWJN3F-6^uFP$!6@yiM9sG5tYj z$lv8>X!5G=4w*S_A*11HNk{wL@PpM)pE&kiuSq%XjQL!zvgYCb@-O02Y}noz-{CqB z7cK5U*)M=DrfQ>oy1{vzLzrJ)qFRkw=Kk-AGdFLDEPDyYDqp^Q@9^RJm#;kUPGzLW zJ_@>gc}h!tEL(5kT;6Xds0|rE4teLV)YKhyc6(FbqDU|ZZGGg)>wCM56W!!>%T|B* zP5o~Y-k@>?O7*$tKkXZYgm_uf&XC`Z9A^S5p^x{RLctHWB{ zNe#oU=OoG^otU0QPJ$H{gFI&0c6yYi`;txs2>DY)K&G+W+?r;nsW5fFY*^M2&ts|=n^q}NFq?5i0+3po=-uNZXcK2*`V?gd6BOPy8~fyg7jMN{89&Q(9E5Mo70oS> zr%4%@`#Vge2?>0*4TO|I@BGXI@~FY#H_lTRMYaXnWa@gIwAbQDKOIqU&9=E;sOT$B z){IANl_F{G^&SbDwvA=+YW$foIFI5A;!fos%Nz+)$YTqVijsZh;@w^jM@;SRh^w3v zE!Qw}MHD^qqGzghrU`nek+i!=aNt)p!k8&h6rwW5R? zN(#&~;t^hR&_%cu_KP)E_2`Z}pHH6Jls)m};L06%k^Z>g)s*;q3?Im$u$h4@`{xj>4_-V(CE<{{< zpeyVFSlK^G#FD;)pJT)xuZs^SJu#ugP$s(WbdE8!FRP1Svv35{3GmBo-Qp%23Pa5U z7UWr2vo#%e!<97Nd_mMJ@uik~7+1m*BEs4TvFgoJbdg71*0pmn*;{@Rt$ql?>=u22 z_cGf9SuWvk4gjmj=C(MtJkAv-@txfU%hJwXQO{!*4GLaRnyv*Grh`L^N>cq+f-%h% z<5Jxv#XA>2o%tOt`|-;tp5s?STQdsINw+0$+*s|n2u;PgDZmruT=enbanzHy1jMRL z6U4qM7LH(rgdRReKlPeHQ4FT~d zkYPqEYyM|mCO_`iP*MQctt5t6-gOim@0<3Mfhe^ahRhiHDXAh61=}Qz!sDOm9D*7(~{eb~Atva7qEDD58le+yoo^ zSnHX+?EAE3RuZ1ETkB%lJCqcp#mvE(YDs^97Z^f};mGFp%I(@9s zy4Qv&GuH;U{%jY9#q1Q-|1l}Ufk^33QU_%}SRn8B9ABc7J z^KA1~nNbtsq($&`T?oD{Ln?C?QzbFz@BwI#B^BZg?-#TLKg{i-*tiTr{ax@rV=hb= zV{qgp@1b3K_-tN2aK532oM2-+7>u-eK9dUW5rN*YNIS z$t==msB8D%Al-jp*`D=T5Jm`FbBle{7=P#K-*NFnGhM?*+CFpN>Mor<`C3}#MIOsX zxmNREmZ{TwIaUsa0-D<0v3en5A5Lb{ee55g7F7~qvCKuKZGuI)4c)xb#l(EG;pwJM zYKa+`ZHs8QccXyMSFu1No*D}*Ypqr6Qq&(HjzRcT*f#bKf{X5+JMUOJd z{Ok9r@q_sZ^8~Bxu|HXxT}xkW-ak<0d7CHZQe5bkP`P6>#k&EWokXAS(gNw*t2k_8 z>E`$E%ilPA?st)Z_kAt>wkdy1t@}R<*BGHNO67Y$4EiquX?s0@EZ8ukL z`4_<12K?h*g=V$87O#o?Ojdcl$SX6OJ)k(3UYt1-9whiV%9f&=If9uxRu*$d*}hN~ zrB~sSrmwK|kk?g`55X*EoM{V8W!}G55EEs?nHUx{<|AHABN|GF>%1#Tpa&M3^Bv|4 z$JmwQfPhZOY>s?)oLOF8?iE;}%boYbn<_Qi)CC&OY?bI_J>pXh;G7Ad%)I4NZj?1@KRZ&q%$$vf-{;4zzGmprhWJY5FheSv|`JdzD*C1!rFcMIB%TAvfE!b~fY6AGahE^&`n6S<(G zJVpe2NRepFPL%W>1cAZH#yIY6K8dGppvy=A)g?utzEs6qt|EdPis(t^Hv*Hvaar8^ z#MCi`!-Io{Ak|6bpGnEfy4p+= z+q-2$%8`Uk9GnBbD1jck`oUSe)qiJB16`^`rvpA0@U%jWhWdE&ZQCE-2i~tfc?n!h zuA7gEium=O!X>09cEgv>#9a0<`8;}Tka}(R z9>rR_vtk=`;j{Foy5eiL2A!~#<5TJ6i^<(Ogu=Nb{aivm<$QiV4{zU(ndB4o68w8F(1V$`-&P%RD6JDB%2r7p*ulAHnoAB zJ9{^FZ#}%<@AU`2cZ{8Ymxw-@2zGs3?B|*t)*?&V%9#GQT#Uhj1wo?s3p#ckW=98K zEdB+szx@v|A}mJVD2Tu>R}^w&%brszCD#wWPwezJMmOxXL+nlyL1)#26f6Z({rMm1 z7*X2D66u%&AqAj0X8+|oj3i(U5P2a~rxLu*d@vHdf3?J#(9Jwx-u{H|P_c|&%2#=gL*EaI%_2DaInFrt zla1j}FcZNV1!^8~kANV{&t7xs!r^km-~HxY=2s*C3MJsW&HD_ z1)3`b4xX0~7iPYzH}V{@4#n(vZ9F~w{I{PCtrH5-KQvm#!=ivIWo8gkgj?xRP9X>J z#tCMbglpKV(eGnpXXV}3>&;DnJ-f?{8CW5YX*cFe6UX>n@7HC?*h2L|_i*OE6lRg= zy-CCFl;(tkFRUKRA{LPRjtz)W>99|1BS3;3%>TI4|&s z$MX0EF!S?W%HH9PNA#92TaK@JQ!fP4Dllp$;qCJv>#ahAJx+%-y9uCIG? z``Pd;$|sOdwAZa}6(62pck(_M0L;8~NxqMMe}=dGG`jXLEMpeCTKk?We{5eT9norKbhQ~X+e{qgK$fy+kBdK)%EHd`JqI>)=5ial zEbXR(_bouCtM^i!hwpOso?839Uth<5X2{^~%UPuu?3VNE!arN`dGjfhc~-E1^i}nF zfkD%vE>7>e?GHEH_imrMcY3Y$*|m_Uw|{f6N?QR(f)^9{fvk6r+pZq1ySVvP&_K+C zzdcy$Jd;vsdS7ED+QSU2g7n7LIDTjCrYP+BG7D+osU(HuCGp`WN@MnH+;nZw_Uq;@ zU#2!o_MRIuIN*1Sm%1ArZS9k}ba4a_`$`zqd87J0g29{mGE3zGp2qsq+^4GtdesB2 zp0HTn<#yPH&QQ1xP_`5mk^m`lC$_XspKiecOcJ1tp-C@jNQ5~ro@M3S52+*AD@!4` zEi=ZZG9C=DjYXlapr*=a=Y-bvUo~z%aQGdRX;ZLR{K^7%_H@fK2aR)psH#*2Ea5f$ zAokdx#?67M2bf4!uPWMxn}-6}-JAUJ1v~}iK}_M?b8Ea$V0983<6iCB>dra zu+I)0V#zZwv^>4jSU*ERGQZ7rGl6oX9f)IfDQQ0b{i%G%irJHM2EP+idg8~QdanE7 zqlv?UVkhL1wq@w#<=sg1jx$eY-$!|gpfh)*lS@X;Q_bCddMJEt^r1_XDoXpKGU4Fj z3|1$rbKgNkw-6g+n`%*O@i0a~6aa+)5Ww`gy#1l!(zMCEtD|FIH5EL#d@)Z;kKK0h zc8Yk$$?hJ`blIZ(ypXW&e_V#YBs|HbWc>tai(%JXp0U_u^#}KLe_MoDeC}*AX>2f7 zQ$D;`PMlno29Qa9hqWR+JFE7kDB4~lSNWd5i^A(c1&c!6Cz}gd9~|PkSF9?bi$;f& zd|L^9Bh@1+%c>H3{d zhZm9*!}@PJ)&)+O<=`Xh_k4e~`%dlI&{02I%+-bCt~|lZh%cP@+a=(z&-dhi0UQ?d z9klqMobe0ba{t{z#rZKy=g0QL3lS$j8NEqhSq$2}+;vt|JY}=s+eA~I&|YVTwdF2U z+MsoahiRF(YS7lie!TL2c~kVge_75y#@h7d6n?m3bK;oX+pRxNTW$o#KR8XL2YtU? zEdc80$95ViXg~&M)3{^ML*;UOXc9plaM5iRL~rCCYG-`g#(;7^22QP2%4t6HH)Xe6 z=Nm_*+jo$b9}7NMf`QB}l5CIc1J2Gli|6KWvXfS}XcmZ+dE$l=CD%--rvR=Zx{7DF zFp~2)9m681VN#-ZI*PnIMWc0g^4fww1=)qClIySYCAFla363ChT{|S59_J2XEMYbl z7a4PP;&(orx;AdW_rUKu_r+l)tXJ{?@u8~|pj)B~brLuy@|MMi+MesJ*y^(@B$J6T zdx~+?S&@!RR`o%pN4_7+`R@FuIr-ogwZ)DhSY~4w(W(2_PCt*u6qWn;jGxD#)XU!N)jF2U<#tk1 z)uYT#O>nH>xIDVMrTVNMa3SH}ksuxDZAp^!p}s*kw7bc9V;up?zhzLCcM6d8&5Kv! zVhZZjHrghQ_9eI98s6vqyj3GY!~CB--yeIW^*Y6Pp^ThU@DjFM+Ag<8Us|tx3Of2` z>g}VtCs*8W9BDuCTC{A_133J=Ht%KVw+Fk0b;N-QtHE!B|D_x6+)txR%nqNuB~y4Z zXhEi%(P@*3LiJi%?5qF+00;(7Ur?Tf^tgAz`M+-VChwCicW&9UZ@sj1P4w8@2Wr>H z=eJ46Uujm@Tzj{XRd}lY8?;AA+%z)(`)OfE^$wVkVd3sjY5Q;--khpk!`W<|NylM42JrH4Z@bR-Aat>X+R-X!Y% zgRfqO7H0fqiNXZ0FV={9Q(@B9=I8NG8?Q(jk0wx)s6#-FO@@TgBCS%xZbOdSAdw_1 zt=S0#WXeWH0dwuBt#~DWkIq2wAR_mwFZqeGUk1ixaowdf~D?yfs&-%lyT|>TohC8Jkh8r{dkxMZH3YxQ~iiQL=&x7T@x~?7RKvO+l)H9&zT~kt>F=W&xPmPFLyOWg-8m7%&f4T>{d;<1-2Eg+Wm?zjO_tP&s039NcK?$sq<+o`YQyh1>A;w z290|aQyMt8X5@wR_!ZwSBn?k~nGVeWS6s&*C&}Lh&nZ}yQ$WIQ-%vKbumHr=AS=(> z1mYfm-&H`i!Uv)9uE);gO>{#(R^Z&e@B+;2Ur@8XTfB^~i#J0g1Vm5ez6Yu*qh&RYr0o$0rWlKQ+dsCs6f$&e+Vr`gH`?-(GkTq8>YW#I z-;;C%5x&}JuoRQ&T{KIvL3H+e_l^qP6U|3Gu<*bg5g1ur3jb z{E@Jtq8?fEH1pJI0nxD`T9w8m_wj{j`lBN1H8J{&;;nMd%`R3A=Q*5OYU6m6oG`2o1OmYbGY{x|vbX4}D-r9o~zzS7u*4mZg^ z%->+92v5k=TH3Nv>N$MKQeMj~sV|G9aZpK0S?;!Q^+T^CxuQz@bYzaWj0i(JDGPZV%6iDuI1bBV=%$*pYTw%3Hmsm!Ql#kGj=2^R8|sM#!;2_nE-|lZ z?ZOtz>0x(Ki?`^-Y;sbliP;O#oA=>veiB0}WHoj3qB2Qj3-vvi%WW+ZGfnxBxwowL z10lJIwb+5^GFQj-T5pCT`e9fzl7exZy!;FD*@YP5dsMdJYdlUxeXosZw?k_7OB?Wg zGbcw&WRol80VoVI&3`{H1qI*t=y{N|w5C-%y?*e%I96Q)l^1`wuNEe{g|1Y40V-lK zb1dZMJD&n|WF>^dRcANsMLae4^ebggzS|i1c-{8vP7q=v#6St=9fHG*0-Pv;BDE@$ z>_LUAsoU$?RT$qN^YkB}Q!)LYoQ7bdswb6PX zr7?e!RpLVszx;MyUEzZV3Df0kXAvaZRP@HT3%`x+fdfHlDT?oQFvF5a^PPp!q$P2) zdqLnD5WtmU;E+&=(k=0q_K%m;Ca1{h4)S2fubxPLfRHIhL{p@je8|~4k)HjK98^%} z@#w(fD?9cTvuVqh9yV##h!2AW6*>=?91XK$oe#<$TQLnfzfKk&P`dth;fO<<68!6` z9Dj+c{Hl5{ugYN?zxB`!e>B8SkQeQhpM#P1ZOD7{zJi!kar$<8LOxwqb(T&R6w&du zurL`jLysaVb6*_DyDl*a))=6Wf+g^d_plFCsjguf5e-0+nfWOw9|`(Sm#N>6Xb4V- z5VzEwm6HOPCCDkg(&h`B)-fqZgXIb2SBB4T$MJVQ*hqWfnpOr(OVAccB(2G+BYJzY z;g#^z)Pfs|lZRR6L-eJ~cgLoxWJHOlQ){057ApE2nBtBQUzWBN_0}Uo3$?&%xkbPeQWv*#4VSf0_n)12o`8c zzte4I@SLLTQ4bTZ=#XQ{(gY*cG{sUD#t}@<1yD#zl*TwusD`Nz^?)>TXqdDWUMDb7 z9E@^{OrcRctGdx*MG6s|LA>hK6W{gf^u+^dhkz>3WbhMsq41}*XV`xAR3Gs8ikQna zrpvyMKEEDgV<<@p<}ET?@QEP%5XIo8twoYA3;`N7bWJxA!CqfemL;CPt|ZET2B2;1 zF8J^-t$SLmG*e!9r^x-kJKK3mHlR;Jen9#Z44>z6)!T0_ZQYy8P#sH!&-+HH7=+36 z7iy~wBfqqseIjA3Q|J2D=vBlo06Upv_q)Jv`c^RT_WW%H+GSfxhSx{yb)QHdwCJS* zx)>ZU7T~h7vQ3*eXAWjZNpQUDczGg^lD4_6AjIZ90kpc@Mg}_~9)t@Y0)}+ud zz$qW|z8*jezz8YeEykya^tG61{~xh-Rv zsa0}@#FD`WTau;rL!|8)nmW+Odp(*)$zt59sP5rjrW><2Z88x0JK zl_w-2ydsOdkt_)2AVeW9@rZxhFtp2^DXVSB^tGj;sp9<)^!V^Qy!<6=N76*o?8zEn zI$#vX&&zN03t;Vw)_(=CcAa;08{av>|Mth|Y zaUXmJp36Mg*tPN%s)?DMdgvbVYsm2*PbORV`z6kOTq~@mzay)Uerhj!{>QoBd$y#F zzv}^(NU&5Nghj6OfBR~M%B)%*dS`lWRlbC$&TnhVy*?D|6t#^%+EQ+>zcPGY@T)`G z63^AZO1>h#;a<@obFj~^z51hCxqsNroyFzuVdu#c2A?w?3P0?>|6A1c98cTJ)Rr|M zGXR4sb5YtPjl!L25xZN5w%sGV^2n(B|9QEqkQIMn=~@1ro`iAZR3sQYzbR7f^5VY3 zqt{>M9lxjXrQYw8$H<#YIgkEZu~~#9ie&BFuV%W(9TAb7QGm_{b?v7&+V4LJ^+NMP zzGtT%5OPmxO?}M%uUoqN5{F(G|8%*#fomrxNB*jQV_>l6($1^~AK=@7#drmb9WhDS zIVYJKjoZ0ZE++ZnmG4`$Z~c~kf_H@IU67Z4z=e8F$iKDhBt@*FNv&~^xj zTitr$z&mgpp@62H?+1b>V;lEV_wfw*7vA=&>k3Mb_T;v-fd*aW+o7G{az!G3+pS^> z0_kgrOxojtD0|>b=j0B#LzAeoV`%;yxP(X;nx8T1WMB)-6-7UPp%-#O|J)74!6zNP z-X@LaWBE43x{{m(RyBFkJX)jJ&%tyUALimkl0yvBUm{7IMOh=!Nx8+SmCxs&Jq!LV z2gMKi&$Y)oo8#vKFxO>ve*PZs%N(fgjIN8o};{0~u38F^wp z5?N(*lUYKJQ33rWdf)bb zR;O4B9LKB1eU%1tdjq*_uddA;i5dp;uNZbWD-d4sYIHp1WTlP`(+eaT!1fw5zOH9r5;>|HtAy=hXQI_|m6zE!l2aH(MGkN2Z)TN7`Tem8 z39hX4F+tiDUkM zJNRNaSXqZsLm&_#0?RNu3UJnxrmJVRuxUt;ADzLfl>Oi=th?E!NwT5C*}K2f%a_1i z#LseSKrVcdho(imi^Cu-vjU2jc-5y%QflX#&zU(eQF!;{h1T^{k`;XNQTR$fFY@*0 zneIs$e~QHd39=+Pu6xh(UjX}7!zHh83U6;z$iBoJZTy;V3_dHb_@oQT_Wyus%*upFDlqCU}xMVd6d3-$`Gn~gVzC(&J)A<<|x=R4Azgt@>T zYU~TbKoTD$LO^l?rY%iU-yDmaqG1r;VVeYD*jZ{{VPD^h5uasWW1NK1sbnZJN>@8v zZhI82B(gWIaNe5SKx>#wl&dqc0n*z!JO8Pc)ON8wur4Hidehz!p~paZ1Y1K@zx)4( z0{CabprJkkWIFmyI?|1oQbhg4+rpFkN8Qf%tl&nAD06B5F7o=&NQrr+`CF6AU=ZWn z+P{m=9=Gu6k--ul;s5Y2WU>UR?VREXVRX zf+Ic?wHix6AAG|1z~|n(Ka|eX)u<1jPd4<|q5^#j%YEJpzG(0!CwPdqp5D|)F8-#KC*C2CKLP&=Nr0MBsxx~ zHz(uYDdH{Vb#f>FgouRfbH4w<@ArQsji~L;1pBze$^;!SF^)Xj4_*73Lc^IIUFo~e zH%2d)&1H*>CjWWb|4biMJXQ+O3`$Dqe{5<0sV4COmX4GX`*+vd#-AB)DIrrmfN79R_3?*$yC#BD65w`sIi2r_N_bgWcJt1?hD=l)5S5ID(OSw2@+2RpbeFsQ*p-)enh|?_cB%6y zCEtZvgl)J!la5ot0r?TSXi=n-fJ{?LroVS3A|WG;#Y>7TO-?G1PK{1LVbzDt@Xw%t zkA?)hfpXTUVSIS84n8gwDq)>&ega)kRX1#bwW1*!kYg^J1XTt5>bfgg!|PPH;yX)j#MJbE~B;k#{^5aJnRxs+gVnWBb4Hb?mF&*`?bi%Y~2F2CLG&7IV=kaR(bu&nj62 zdEO8^jW;zMyv-k#tsxlFX`~EJ&*y~P2S&pKpzjSEXfzbXK0QK{lt?ghknJ))QWVk; zm0n=5YiA$yEl&5|Ts3qe)>>#$ci(Oyp@*FE3^xxx6s6ADLxje(us5x{iB@~I7Vk1T zYO9MaXJKmPkp6bj4I~@zw3~;d9ru9uHbQD3)5utAaE4qTW~Db|r41HoCNfM^1x=@s zmqfNW`Y2MvSVPXI;4)5+UFTtVm3MvWCa6!w^W$R;A`u|;eKgD+j1aOpzaKcpGA-vP z8OvSAXvoVbys;zrmm&v&L%>a$+a7<{wNsSQ@IJ&|`x^BJByf!f37iu?|Lx><%P`7v zS~tK2SQfb~ zJ(L8Hj}%@+#cJ*tzU*RWJp|Lvly^|yU!-uUn{ZGk7ly`pNjixN_UJlceZ@#5c1J>G z$ur!y%nE=5+DXJ$dOks)L!JZ8SwZi24Nrg9H@lF!rQ+Idl*DfFqGkVV7%m6z5x5IF z$8`|$P5Y`BvNNs=m(=WkddfLW;ueh)gJ8%tl6q1zTe}q0b-3f$g3s@<{F$`*QCFb~ z*WPUNOT8L)O|nhd_I^`|1pSHK$~srJ!))$?UX^shrc%U#H%UGaGi1p@WzATBee39W z7<@1<6LB0ZTZ!zOxVh9?LTFduZ^=;7HME_#k_)-Viz=m8mz{Q8nmeOXmCg-0l1`zA znV4f;P{`rhge<{!huo|q#3c6$rISML`_BBjj(43&;;laQ3vEx_p~skbyeoYpjo)lI51;V+06qTaK4_1W*szP zWKjBC-*Yggp73fqw`EkRamGW6dc7UvZsj?+jH|vm;+m3; zpH;?-s-;SVh_Yo0IvU##nZT}gL12s8pygViD*w}9AOpNb_b2T&8+Xq8it5=M6FQv* z;9y!SJYO{}RWaAoZ(X>*5f@b*?P{c8YjdovmS85!|WnUWwCtOaN)@Mt@*6nxH5y^ z?j37E8$FspeooS|ZA|#0Jyx940|H|=Eo8rn)i%iya}+PRpe<3@xnZm|kLSU-0;!3+ zAZQ9_FcWW=cT&yMaH9puC#r;?b61|Es+Ciqn-PV^gx+N+2u+oRV--bG$sK6%>^MkC zWstCg$fKC6vZ51)#JlK6pd_ulNso?%eqA8hY9!4p*_6lf=i?4z6MZC29WL>TWHjAF z8_T-1&++udA1XAq?R;;#<=*!x2frwO2g6*Ae0@9~F!pm&GGlt3;BL`ipR? z5wXdsI1H}z$yFRgu>m91wWUEf6$R82#19r#L7y)$`|Hk@yf+;x=EtMbaiDQ-S$dMG zoyN2!*6Bct4Jqy^X$olApIZ z-2^)eCGdj37$zA|1wywVieL6?bjS(ig&p9KKUHhE!l0850|sXrs_jm zBM;a7!>!<~sJTd*_-=v~7nru4MBJ?QU8R7zP^Bcd;)Fcd10qtk5~Kd#bu z|6c%CPECFrKG3_&K1(`&@}H)?`wzs4Q7_6UX1Z6>ox0opht}GPpkYl%+nK0zcegn4 z#vsnC4Y0S@;fx*`QY_1@caR#G1LGb~UVQbZsrYGrE+Ub;D9VShLWlp|+*Lgk4?m*m zJ8}?Z%&(x$YCJ0Eeuow-ZphtKmLCL2Nyc7jG!Q7U{yC8PA92+e%9H}GZI%_^@ptFO zRT}@X2|G+aSh!AS{S{9&A{cEJ5roZ#AWYBik^2jj+S)dOFpv>m@AzFK>xFDloh@(H zB|RaG{Q|fj0x*Svuspa(dZ&Dm>@oeV--fMiy+_i{`8z0`uu@mAJA32k&7H09&&+)p z)I8JUIvW8Ak>TXcfZ5f5fAjEzv;sn`459a>e|{K{KqGb*N^R5lqip|Rd;6k z_c-KKUOs5cN@CTk)_s^|FRVaj{MtWal$SMxoLux-U!yKVi1POA>F;h#*hE7azZ$~U zkc!~v1Y1Q}ur;`Y2amtHyzSnh!}UwAJjbW5l-3>H<@V-u>!ZzqUK9KF$4hwkXs4Sp zxlqGwlkEzKqWpX^Hj9gSkE17ffk=rDw?|Y~gezT|Q8`jRL}6wgXy~A;KHn27K?EuV z08mN8{(pYcpx-~s4u>e?6zn@F0`(=m4OO|vBNN})nRnxq=8dO&eaOedYS><kh7XEEV1|IIvhjXK2?w|4fq#wyk5wK|Rq(&&J#cHp{ZuLK1Rug*)nhMiBU4E6A zhwFTL3PlOxWwQM58|`_HN_|cFRf*TyJ$ctHH3r`M_Vqp!$z1qN!SKSs{{ZrAkGM5} zclj2d2%`fwF@%4BuGuEA7rN0rBTM%CG007ya+pJ;dV z)sR{TYpyDHzh8#u`JXmBD%L!qN`<+$tg;&wqNK1`mGr|zs+`-uf z(6_gO56>s)K7^Youw>S#vti_kbbue55RD!tj%gu8uQ6e@yi8SNb~Fl&A&c3>S4e?l zi-*WSaXi*z08JuUnCcgXY9QwrUo0tm8ElfRKdXr#x)qROTcBDLES{?E$hZHBs0mjz zs2Tt)I6v|)cc9sBJB@rfbU-7Dld4iv<%G)^|}>=d1E_Tm-J5VXK{iXlxh2v-4E3potZiKnR0 zCRjtSNRy+Jt6dO9dw|%Lh&ot%ZHuxBf%{HLE-$Qs(}gyYCZ$3F)46vJ!Ggr4%HtsR zy8(&A-eP_j6HwL6e2YT5=9xlq&AfRk{tjJqNEwC%S(@j`@e+tSsS)Ki02%6h&&3|`(8V(6=`#192J>1|r7c(()8LoKQaE2V)!vEzKX z2}-BgdJ5(+@l=S994e6Cg3&!1A`-WNAV{&icBdDNz5sA)6d_z&%TGYJ?k)Coc6jze zvrW=q&z%oE-vF5ic7u`Z8f!K-Q-dXXe{-~S`cP@DbGx4k)e$~9B*I>B8AC84tz7+d zuKOt+F5a$NQAoGBvI_CoPwjAkUeT4hLmX|tJUcT`9G?bQnNqf$FE2X8E&CkdT>|1c zG>PczsWk!cx$;kut#WekU@%mTKy9PXx_2T;`x z4OLD{O48*YHfPG(gDL&97YV71Bz{rQyT^bV4nQ4**MT$bU?+$Ryuw7}hZ)%fQQ@bA zD}GY|Gl!vmh2%SwN_S-?OKOewKu`9a^+pV*O=)dUi%r`IA%((_G=#}ANGde9)TPuB zxh=XWN(1BI(OZfI)!ktMPAqCSX&S=3ig)yI1BLR1(YK4f;Zbz$rjGCE)!u)3-NRRI zS?OkVM=LvP`EmHZn+K_hp}cZ38XitG^8K=6rF(>v_;~wEd5?wZ5Pw*RCBdrvDw+iC zO7q#2?KwjXcNsfBkbUpj(5qkVqVKSf*VqUDd+L!tXDlJjwv6M>ojKL>UG)!Fp0a(v z(o=&mhP>HyRO~N+SKm*|Id@^}O-$sILn($&WCmNf;DD3A@mveAKB%SMb5>ghULA_i z-UYs}NBMC0J|Q{#e|md)@QwGbEGOk8qXu)tX$;gANX`kKxe!PIlnrf5wlF!pY=+nZ zZ)hDXgSC|7Q$H8QsR~x8x^_e+nsjQ+=RnotWVC{%avQC%Y?LOfP*k*&<5^nks|y~7 zc#$eg_*bo*RDEz|9mdD7aRJ)R+7Sl`dZa6Qw67Z>C-C!-ZXN0D(NW$dTXQmk46r7f z#`i4zn$+a~c0vZ4q;Ds;Yv%uy;pFf9myAhMAp@!Z&NR!?XML`Tzx)ebWkdB}tO+WH7<-6;yb(vXf z&usSW$;|A%-}imqwy9@TNwFsJ8gTNc0~fFTZ@f_pr@uN9m-%_B*x*hP5Ex?D_~~@{ z{^dS-UFaC*b z=P`cua2ngwc@TB&-G6b({tK~7jT+iaAKZfu_l@>QB8PY%HC^OK01N8RAEltOL3FWE z0YkL`sgBK(BvETWHP1_rO^(}pxk><9v-pV2<{$<_+igc`yh5D5=E)5Zg%O240sX*t zwSX)5Ts%CEyzs=fgqMH7)bm3R(am5M2a)8@)4HO+cUmG5KK=QMJeS`)Js1R76!ew7 z&V2BvrG<}Wkw8C-kRuqL+4}MvqBCss2Gh1MpRPZ|BZQ}MPpD2&x{fM`8*U^m{^u9^ zpRqmusKz;ul6`lIz0iAHJYGM)8BIVi^Y`E%|LVFM{Ldh`_#VlB@aH(A@w;h4P%_%t zi1w@B@}p5-T}NQG8Rb2jQM}?_H_WvNM4v)18PD9(vKS~)19RHGZy%^MDv>;{bp>;5 zfg)G^EOjI)bG1;Z$flh90aA-_o{#qiKR>Ot9sIyS749`AcoO&QrmMGdtEHbkp@(8O;<<|6z`h4CXrXdjkCM{nL^BcK`Jt-X1_}H?dc=#VC?)SFMSKBY zs{~<@y+ve~LWvvJaS?}E{Q}$o=jP7Cul@r3Lu96|UK>l;&4G~OVdtL+f(+KJB7}ro;^S@yJY5{_5unf_ zvB!c&h-v0rXuav|=cn z&HH*5sJMWnOlMX7akGlXsFWU~8BakqmS%rNg54S=1pw8(r_byKt7yG~eN&PfU4~-p zo#Evi3#F^+w$ZLV{hvK0$hbvX@p#AUg<@0M603diA!F$nqkDIhsM)N+bqGBewO?G} zloOry91$C5t%y!G;bXu)rMvT%2A)D>OIj9)OR(3G#RpO<6~00{Kjxk3g91Nx+_0Gu zbGW0jko9)$3pm~`Z|HVl=vBJqhoj5AxyuKI>7#frl?!;&93A1$G2m=#hy#y5f0lAx zLcCw!toYD5`v#i%WDCh>+$~ag5)CCL%KSPANdG|Bm)5UJ8FHmok%NX33yxu; zpJgA{+!93f0uXJ$&v6I#gLmd>owooA>@fz%n*5ZcpCRZkz#IKT<9JRzbTqk1aXUKd zX>8APip5~|k5W{Bnw58^UkiyRqhq9TUIF(Y(!JB{*;fQBQmFJ=(i#?1Gwdn$;M*G2GJ1XG<3Y+bQ;4-6S0y;!1JS7)q-X1XndnzRSS#OSg;t z4225A7GX|lSCkBFHDytQf(MXXN^%ozf}08tU;mx`I(}fjl#5$CE&>xsTNoVa7W>Pz zuazqgHVG1|7;t)u33w0SZ3z}PM+Fi+uc8gr)=?1Eh@3=3J_FmShWF**tVCq{nKHWT zO6RT@DYVRTb_Wa7lQ!I$>+0tn>bw`Rosq!C7)Q~hp)^4fUd$bi9HOXN08Bb$0@TuCiA82J^8giHMu?Rw1du1 zJ40qqlcmj&2ly&YfjaLm&pmWfABIge(!w#Ur>Z{G0avwvy`nt;Hbqs9dX!r?a$XJ9!o6=6-@SfhZoaiWc@yT| zJVedofIvqbv54nD?Po|h-&FfZTJRLpI}^-}rkt^Vj^4_~>3k~xLD+EKPz_XAhgkyI zRc5wwNxiu17@tXgdjlR8pgo8M9;*q3z7s?bE7#p(AF~Tq(Kr)?x2-15BvwE`%u_?(UBV7P9ylaydENX_E+hAc*BGJe>#|dGyjh#LWNvN!>Je(@LR_hPyD5j;tV?Fj^ zcv+V8cLz2M8r>|UMY_R}$Auh)(E=aEHr3Yh zt$-VjI!3+wETj^LG>DM)aK_weoJv7RRfW+4cm<7@F_)$4;G`X9Z(U$I2eQQjnQHyK zr&bwXY;Wu&nH$Cl4d(zGSXBsBV^rwzi>3PdaJE(VZX)_4SH0QLk>zLt1( z29!NjQK*srIRSobYL=3w=&NemrWHQ8FDVL+Oc13pp@9QX!k*k9FwHxD)j1k*qand^ zOZ@=f=cL<$>^3rs%*I@cb2z=a>ZYJbCo5Dj)Q)q}VI?<(Aet7=;>=E0&MR~+gbm)a zxdH?-iIt!vqqT%nrLy2y;8TuLun-CZLm|ygBAYqrIw%Uf3PxCw2%9Ey%|}9(Sy&v@ z-oo>*0r!88-2b0JXd=!cIM2TpeD(YNK6eiXuVE*ip@GkpT>AqhSC#lgjx`9T|6LTK zKLQS2i)?1&e87cR<-(q6U8+LVudYMY5Lj%$Pwg_ zJ_8D(Zd&J#+x3C3Eq9CB?j%iJ)wos`)l`dN)5))SUdvtc)U;v#lXdIt-`hM^nj=9E z(6JdK6HMGI(gnjM24)uI+@6HKbwB=}E!%!qzbUQK1hU18{2^%{KNh3gd%F8jG19Jk z{$25?EXDq9Uy&cn|G>^)(&pYMNMKLYUSFAN;-JgvxmWQo0;K-0c&UG$suX~U#vcE+ zB-$u&xNdR{U-lQ^AK1D(1g3!)DZ$&-4F_p}bH!NXegXXKwSahFRFm!6N1P$nJ;L0j z`F)Y>)D-%>-?;Oi5b^&(j;D@CBa5wU^L1?g38wy6%^yE_s|Zd@j+pLI82g!ib(;B4 z&UpRx&d>fXj;JU$Y$m3^_mDL*hvR@D7}pyct*J&a?Eiua{UPf;`Kv2+9+vd!49=4b|BP-PSv!2&F~wiM_b zie4aTx4fMzn{I&$5|@{2V2*}_7ud@3x2?@UU zZh6bq2TuBPHE9`^%0e_p_XJhmMZzNA11TjA%VPj>bVx-;pP+rLK~Jl8mYqU#_|pv? zO_0dT7@ktJhk`h;=Pyr?5?MMLFZK(Z3-li_vP3jJkyFF|@&CuYGCDWz!+`^UDYtzW zhhJ=WMw9S{-oM0k*(Y!jb*7rsIR^w&H6r{kRta;S#q(_?T4%KxEi6X6f-*5#NbeC) zou=S$8Msr=)qzI|0)QcOAwobYoC)@fW9A@=N=*|=I@q@7>+BJ=1r|Z%FQ+Cbqzczn z<5m`gt)dD&INBoZjqLz0Bk`PyE-EEW1uo`KvlaleQQ=LY6-XjJuKgPR@hMhbjepWE zVO{irtjEJYG7lb{)&Ie~uh>h)7uGA@$}-&aVp*3(cEgHW1JKr$hs(8k;W|CoK3>kV5i3c{waB&h8x5vA^t$J9mRr(9LMQ$ zTr|W@h4#BLmQeh9Z(&D1d?pI6d$p)1VCNC?yQ&DFFd344gu#wD(gKx_;mx5ZoB^H1 zAu{9K!GLUfE$KJhi{>pVT~w%4aPt&Pji7s~kHh_-U>}AewrG%%1sBU#E@M=#H(v!( zz4y#RJ|}koKx1&@3h|DTeY;?fU|(+;Edkpz*N#4l!%Hp37Q*3A)dpv;z1kYN3B_E0 zM0d`eik8~qo-@jLyknf{w${!Z1(y-8X1bp|iP!5buhr4LZ#5LLLKFnmRjEu!_ANyk zdRFShE4+`qiImwKsf#JzG-bvKrZ8nmtY}E!M;Jv-3UfL#y!RrZia=B75v;ROYTMxh zS%uK~sBmIO1_GTdba;!xJHHARZdZH7YW#Jg0Z`8=6^52SZZ?UH0+%@?+p)3P~__ix3g#v5c-$n$hQKP=hD$a}J z7{er0!-UcIDth}n`#Cs zjsi4VL%{D6YtQd|Yvk`T;ZNtEmsI29tAE1MzkQ5CF(~hx{_#}?juR3p*y3a0l9C7~ zBi6jBrq*_0r8ih{HPU#ctsV|rOEf?D4tqeKR|tV4o9`ebCx@VnIMUGa|Qw9Mjf+sMx~0t1#B%O#88XpnfBR+e9oY;&&1VP_C!$% zurrld63Th+2~-xxN)P_~F{~g5zd^==XO2?Hy`G)UJb2<13z&jNQAOo>cl`eU(%GHi zP;_BWFiBKe&jC2X6XcvIDAcS~AX#;ir%P^M(cvQ?kP;k%%ND^ya(2Zw7WL z!<|_z->}wp!V%AhJ{_-j&7R-f^=kX)g7Zdsr{%KS{rZ!q@BUFdf^{LIi410- zUiKwmbBdk}O(985!_0Yj5ND^3jyCgC^t7g}lwQqWOhKy-5QnyJJaKjkjCmxa@QL-P z^>AR_Iq3U-77D0Mll*+o|6grFSE_Ux8#C860~=2D{>7&D6wk6e-<$;Rtvq?mg%yrQ zF?VXd`FCc^|JRWDuhp>IhdV0&d-TYweUreG)yliI> z#}cGN>XzeQ$|b@4Y!3Z$L952Hb3bT@jV-^i`B3OZ~?xl4Me>-IHYa5*})+Wkz#ohn_!A0gc5 zM(UW8f31%pttu#I1^mQkh9N%VE}Ic=9_>!fqQ>%9jd|#{5gxOhx1kfeo`d~ zwxWIk)SfVkm!zllM|`7_9U=S$P{N&8G~N{ zu*%w7ZO36Lv4{?i0lo{iL^xVe?1nO?ht&(pnTnP&Pa(`nWUMZE$Q8@tNAZ)wVX-(F zoa=X+V8)*UeNHisOFYw~qtKIcH&#)^i&E8-T^0bYcDJwju*w0m(~uh!Qx49fKY*?P z*tH#~v*n@JsO(boHsaZPSUHoS0^9>qDs1SG*a>7o?jaqTmN@d8X1EAamR>ubFN;fN zIPMJ4@)kMFR`npHEm9vzrJJ?a8<*^)<(8w-PPTIR@l*+p>HC zykfA_=fOo}aAQ>|%o6oh|U7 zA;u{pooC`P&iX<1k-;u|VVZbuRj{}y;WG{M4is{VVn~jcm1SJeh7x9z=nHTLzZg;` z9li21*!45oFX16>wESEkXTTKhKYe{^lGAJqj{&>teEHrtgj^Da-E0vW9nu+gM1#3p zBxpW#j$wrrVoMRcb0Vm1SikrS3uxn}FEJig*EQn3DDB29w`oO(ALtdU=z-@c8WgT(feWR&V^ z#y%;kcXlS-R2?7&!bn!I_EM{0Wdb!JK1uAbmM8m1ADl5D7H5V79&xKZTgN4+pv67J z+{5UgE3Gfz;vV9AGaJp$JBRbjsqk|l_hkeLP*r=S_XL54{NC|iY12`>4V(MhDMY0_ z!-Orq%V!mrG%P-`^%ubX)1d9#k7|4hcK+zV@kUi5QEw6otnj-0^AA~cCx`$S;@H(UGvGPte)`osv;PzT8Fx``xKc`AakA#|z9rqgANYXkOh_Q4-of_6 zl}=FI0-~l28?$2n1m)n5%!nD<(v%v2S>p++Y-n-Vukd9Y7*MLMis4Ys*u`?PZT3Em z1Sf51jz(S{G25tQLaEiL5K*dfy{$IZM2y%LqXO0y<;i-x(Q+rt_d<|HXM8aBAMfG< zD1GG9*sR`9lS@a!rHNp5PWzhV4G^?>;3aVcP|+5_ z@bDKS=qW?R;OEP#nAb2a1k55li*C+H4AyG%B5`_5QiptR+Y-4BWg!=gXi|Y{*eMxyx!Cs+VO2|SXl8)`xZwT~objqn z@do^C1fzI#!c-}?>_Wij6w!x}K@=}nEEB&POGhjgUuyl~1#B*Hioqs#fAJI%_AjcF~2o}=Sl&gKbQyfvu9BK-0g?S&< za%#Ebq7C4X=3fAC{-9lY?q3X<_`jNIe0t8IkL%*GILbgOmN4l_mLmjUp&0= zoWk=)ny!TCTKfLFt9zqb8Mms|VYOMM2>JCkK{M>%5w&E<4I#6eMX4X4(T% zOb&?7*(~nu>(uLd^obYE4POJHNIN#JPxMB$1K;lBbAwAZ`dUT?;|!odMN3waPj2(R z4*n1ss3y3~!BgMd*G#}ld?T^_$j-nA-|4MGE`Zy8)$;i*_UT|t$^AV2yE#1N-+lpd zGtZ&>a8nx+nH5HE4G2(+`RJlj{O}q-5M9T0hdJ;?Cm&(z_py;|eyeA`n}4}jGmi_# zpe4V$Po^-zDTzkx;;u5(5bR%^4$-3764jA#hBD0C1atHkH2R87N5?bQ%D8$%bvL|D zoQpCIpIj817)`dtmu;$$_`5VFM|RE?umiv%-Bz|- zl~vlDBKmk{NQnn0^B7W8_#p>v@yrlqs(~CKGNp>4UqK6Es;8N_JB$8EWs=PC3$XG* zuTa{5XS(wL*J5vS{J-9{v)>0(v?f6XWa`qCnULvfvF{@cbbfb>n=dH(nnOk3cnXSM ziSPdE!=f|5D9+LN%|2X3jK0D&;(#jY$^CTX^DQ-{)&y`F{d{o>(Md>!G3WD5#nRTA z7W)K5?A+>D5=_fIJO^MVaidp@B7qJMGKibD6W<>h?QyGeGrphk`X&QFAl=4G_@^TE z%EHwJrz#LAFF`K2H%FeQHr_5OhAx$8weB_o(8-sQMduP79-4Sv^(3UcCNJU3U3^&;B+^ zqV9};CEKgd`_SySG2tO66uWcWmIUw4d*L@Swz+k96cW_IqU6f)EC0CP!U3C4K z{2uj^uQL}U7D^cB{sLg1Uv|FzhMbB}#^gsUFYQdgL~?Yhgqp^;t5*c^McqimoR%mk8Jw?vCqYDLsbV3fQlP3Yk6r2w)m? z*O%SuU~GOL-smB+&P&}YNlASVw$OAlo_@qT^X=Ybep>(A*?3I1OnT{>z6BBSY=$OL zF^bjj8^)AkVVaR!Jt}O_U2Ws-k0+PI_3UsWj-G7ho;9aT`;S)= z^iHgM8uzojW}P_D$OEeTd|!V6_7+4A z{n0DYzI$y~;hf|Ri>vO#Q2g-^QVSuhOKjE6kfX_j+DhZ%ab;(pE&b!ZIo(*^#Nj&3jw;kWkUC8gtJg7bmrj@(>^FtjjsQ&T8^O)~d%eFaU zbrdmQ{$5ptV+nnDEEAcV&gF$Zn*Vd_0<)p(-NJkf8PXnpvteICU;lV*@eAM-GHEg26+{^=h5^>?V{{Um;tbglmLZ>l}M zUj#gn62s@b{%31GH-+l+hc|wYO%<+PX_;RDGTHYh@w?%bA*XU31q9^&<`R0GUS97r z#{JCv=b&WKl`(@fFQ3rQe2~$=%-(r*@Kx|mCf@tWm+oKqsKXSE{mcEXUj53_wF8UJ zyenPF*tz7JbN!@}DL|;0Dl!s`Qs=9gYkC6Sq$5=@_@Cgx6QsU!kAUEIw`)-CU<$ojR6yG+oq% ztBl0wSJ+YVc%^@vxl94F8?>@@HzxV&1bAJ=7}BLrD~1Z*mzt_f<-6?lywF#X!1(dJ z^s;S1E0#pYX14CK8lg#;zD21QYB%dzpz2{Qb@>bA8tJcT>r^bt-lZo`#MVAqPP)8V zvJS-^#~zp0I*bhYJ_Fg6=?}dR)@NMB4ym5K?S0kkgvro;ZV`NPwKa#|alvLXmTBT` z@6(y8OY#}NGPjSO-E%dJNWiLuIzZzs^AQ6aYm{<{U~WaM|aa-h^H8*y|~lY4j!0 zvN=nQik^%q44?ZhvP;+RFBoiY4AjRxlU5=OKR*y7?3zyA=)0LapUqsTV&tySAtn^N zu`gY~Y)MG{0cb~Je;WV9=H&ww3S8)V078OV6Y)O2XNC zZ>SbT7rZ$oHX$CoeSx^8=x*(NDDZMAY6U*G9xQ$PB;&I#;@%?gko@I~+8gzjjhNP) zYG3IQj%J#2N6tp&B$RX*_WpaWS;IGN22aq#+{*P)k~!0hwHnUyi0UC~Vh&@@C$Jp; z;l}0V7s{hSn?&(~gzSut2ar)0e5DcIDuILjN!q5C$3!SIR#=@xmPr~KSbbx|%Py8$&wmu0H1ucG%F=z8DXWCG(E)=4Y{&R(L4S6~D_UYhvQC%@}+qIj3 z$S(&Edk&~s(Mkbg=E9j`_ru{+Xx8^1rhA{G_Bf>XfrL_6o(BrV*6hDYOxRuZJ+mKK zUclFv3utTpfc`M;?ubhP&?2^u=7{1T*%1Mf*8xty=|1XSo5hlV=Qr$iZ%U|LE7PtVUrZZzO;rDZK# z*j4@bGp|n{HzqH+A`U4<;N5o;yM@QM9fPZ%8%ZUTJJ6NvAfi+6shcdVKUL?7*mKpF zK8L|W_l^?o`pI)MoZ}X{*ZFOAgkh`d`LEMkZC&2qf9<(m60<~drEKlWJ2Q5X#hE1u z0L#SN@iXzaYuBVZKdeWLitmSx4jnhoVc`fxD6{* zt+(RmtAj64$6tW=tr>Bd08^pCFtu(?WH&HH(QwBggD5Xt@Uh3eVxTC!H&yIt;>>{+2^*-Ymiw`z) zNguy;X6f<)U)0d%4}`=I7c?a+)C$}%&X$giJ-k9YAR@Y8^)YD;e9-ufqfhy|&EUs0 z_34rn>zaXBbV)li%+MFsgKB3h#t2=dzbV$PMP*284{TbE`30ad*{&l@WiG~VpjK@q z%k{e540;~sox|3(SPkz|uf zqlrd=`fbLvNxA1tZ(0@Pw)o=5v4k#m4qzaqwVoF zS2GI?KlN*9epxpBt?A({Qoz`TzypyH6|qefJ#mZBX#OkZesAI(?m2fPrY#w&3z9R) zugSpgcH+x#_!??e^p+6H{v~<&zf08rzJ(rtMnH!kens>2^{1Ca`aWUUL-9RvQCjvD z|Iq7~A0bHn)dxkY{bFnBXT@wM1&trzuFf@mjD>D^ujl>5t@k?I7z?g14Fjb2F18MX zaE|GcWaBYI%rEA)i@5Ywy^qyOmW+_8Pal#)z%e>+Hq@BBU)o-6l%meA(p!!Un-WK! zhEOX$!XIdZAAN{kvbpxK_P2bga1V53X=lcY)9$C@Rq?44hL3U}2nhdlpSosR~!#gSJI zHu^Gn@QF8G$-fLIK*nhNaH76AJwEpREzT4wFL+aKxM<-~1^3U4sKL0OTGcCrOHNfk zg*4oWul2+CeWpZU0N^kN0f|mK@ld>RKW;^~+H*9GAW#g)3f4D|rCOcG^2Ocf|4N}h zZ9d$pan*#ZftkGPnSu)(F7<;T`4(x>>!`H1=C}7hg#QA>D2~vXej)T}nx{dsVa~DH zD>vQhNf?|<-wLVrLf8a_j>#vyQQ-jA7}uUVaohbTehSNjZ-kYK**isPv97X$R4*)> zJa3D=6`%?tBSG2_&43LxG+8bC6uSaF*s55S$pUkvd$)}6n~=PUMD`siCryhS`H1&G z7^@aVl3%Z0>@Prwf|(8peA35o=bmC9%t*3c#jqGy$`-AvVGGXS>Qzj6CSWebdk+3LobJ<#KSbOQ-4k2gP22-!$i1rr*|P z=^hSnXA##l4zs4zT$=<$#67>uh;1bqrhLk#YObYXjJa<*YX@&CF*MmyJQK2AHn>>WTA}-JF$M#2k+x zj~#R*6Z_}ckiYE95 zf{x(Mk0*_KKP-OZc}pd{bMdsq5B88Rvwn6p=>A5#9GWil02EcKra-^MszI&Fr>2_E zbczGh1j~S_k>O!G3vl~YucZyM!{xU#L%&7a#0#GrrTDssegz>en}lLrgo`u?L;L~Q z({^Z!=fgKQ;r4Z*Dl|2s4C`uA6=JrOU86JgtLoHfh$U9ejxd)sV<5{>UqYzI}M(_xesdeb@r$iB{Aqc+o>fP^_jVJ~P1hwpbog2Y|~h%hi|yf;5zg&r7I8pId2E$ni9 z8SNNKSmmU72c*4%mvc~ffKAvBz4k&cncp>s;I4-B8Nt{0ZOk%|eXfQSi;a0qNL2{) zo1#6$6nfn<_Ux$Fvyt-k-!Ook7cZg9C6VxJa;~F(Nm*^Lw4j!QNmk6-DFGe`>tXX} zJFYgzf|*?%az*jYC$|+X{3H|7;3a+ai|be4x|kKKn(hk0vdh2na+Z?Z<~tFNLACVi zbnSDmwPfX%PpFe0S=xP0Xfa<2_i%l!1cT2RQsrfo^m&_eZe7QlMJ5S+V=ucX$T?<#f(7E@`!r~J{!TOkqsx4Y;9&+Uu+-%C{X zE;1e>%6G`eRTc5SK=5WJKKkV~Aap-{Iw|UoQA9xqZNJGEGJF*}&uz+dv}WjZFs`od zV-zN%@RVd3TH4`f=t9nr87=XR-T(aMXWoMmf#4;RHucZ)KuXp$qb1AoXlGZ^N&;IW z+Ne6>t8va2)k-9v`v~^~WHB7&@VNE<7zEu{YVZ%PFQ=O?8*9^lBM-N9cfWbgiK%AX z*Fo5>I<^BjKkidGahe)!bVWtS1ly^8!$YJACF6th%qTbyr5Fsn?UHsdWn3}tL2}Y& z$Knne&DCz)q4Ps0$M{p=B#p`5cQ|4!9L}W1 zr>?caa8g=qpZR%KjH|PfriYTl5mRoO%B!7WG-i+F4uLBG7k$Lvno_R`wwoj-1;gs3 zC=Uo6}{$!LLLz{97dP$U8wzgQ|x_Uu;6gQ$KHdtN1aLsDtRBG8N05Md0t zu34`fSEm<|O$*_!_G*uCXqMUO>d3T3O}&D8W^RWveB!S{8w%G( z6Qeu$l&*+hlj*z9uEKafQrF*kz79|++H86*QR!jDKPO8%J$3E4$c_GUUQFsKHyj>y zH7WguC1bx9kgv9719%!s!%*LO2Kvf&I6FfVP?6RWAzZPEX$P4@MEUI6a_z zBKQ*LF)uBXl7~*@EDGHx$p8bW$-lTQpe=c;fi$dkdOqbePXyr3E@tk$x_Ys6w=}h` zs8N^U?{hoCCrn~l9^s3tALSK&l}t@w!Nq6@rRM#ZYB#AF?q!gfj}8x>al76UUOnbY zr@DrKHFs*V09G_wh*UWCuUa9YT@+0Bz_xfgLJjBqecOyXg9&b3BhAu;(!Q*jZ=?G=S0+G8j|;wKdCmQD&Rnuy#?DTx z%LQap?};Pv?GY7IJOcnggg`;>9-WDp7(*18>K!oCE7X?Elr5MhCBoJ)T5Q>At`M(K zilT}C`M9eBt!Iz>%{frjg1N10GIhmwW#0urgg|snLV~)(gUkfVm@-fgEIR#>QupT< zk9nIm!aadBDrme;3|7Y-6dV%fR^UC=il*iXyQ zYXvJFGK{zFVO-C-NTg^5%)}&G1}wlOy3(`Bk-=c;Dn z)+%SSB2>AdflW$xehSol^g3l7VS1y+82<-n+|QfezdsYb6#4qUzF&^~tm|D&BMC6| zcb+^H+}tb#ZS4j3SkjCTb$hG8;j5?m5+;;*9f;BmZ(y@3w@{g(fp5{MvU};i>!WPj z)pwNm`En&FP?~tr&(SH$jm<(;>}vKhCn*wnO|sYkR68vuB0;fv1tfI!8M|$mB&=zS zA$9K2kgY<)H+hxISH`nw{Fw=$m%{yZ#Avwlg}f(lM|WMv!`M6wdjGf|YwZ5y=g|EE z=PpwfxqxNx@odWv?9nwtN~^fz`$rtD$MOrTsqvNX$+wDG5?xnjWza-#c>6f$pVX zXokE1Wl&n#Rk**zCY#{AOS-D20Px-yejf%^%n@2MC`-ucHRpkA^$*m`En)#}Y(EY{?%IKqCR)P~@q*X6Pc8AOLa4CW^v|QF z&4VDcB%Keb3D7>%6U49bc$rZVCBZzvAHG1i^(FxGC0fmpl>MM|jx>Srco3`_lmWVi z-2&<}0L_VkHo0?~4>OA*KR9T#_Zq3Z@;0h*P&qlxsX4!0A~}z$q)kuveFO(&+g=1H zaF(hQBg|f9<@twnU9Z0+Eq6O;LLG=QQ);NM1JgNla)q6&zTjMwZ!2{_pzNw8%vI`F zAFwrNT}EKqG$pISIyCP;)3L~IR8iy04HGOj-$p5|+%^l=PX5y7nA4q3ON7tPf%GV? ztkkD=)w+iV^e~wb_IJ<)Dv+221`v)>iB46{4Mk;TwrS|;3SB!h!;17-R766Mq?zj;SuieC~Eob)vB%;QDcluW#nor}R=SeFj7m}a`$$Cug$0QdQ;31h z9MhC98_z@^(B&0(L3u_$9(6+aV7TWnjX96wP*T;HzI>m!r}zk|+M<@XGvE$@K<=?$ zfl!sigs<2KZ`*28EL_maY4&XF?KnuZkFT&jIz;;8AqTS{IeHGxckqPvYkt`dBLE#LidTg%EQmi5K$;GoJG>)!E z-*!v;+2T_kRJy-|PE$kPzQWdks_2A4HUW3dDj(Ec3S=)PDO8rH6gW%Z>MMl5Z63c5X-8s!yO5GUnp;q6WQFa~$9W|gMo0YHj7;i^d{ed&^qB1@iB6MCC&F8h8D^-c zht>K6-)GG#ENwQoY{gyGg~z|92E#~VHhKwrUq;n ze*wPErm4nGw~WlpxyF>SbwCnV_bomq6op0 zTn+_SZ7Xb`?h7&s6w0uFyIw3 z0pZ8>60!>XWX#uUH2d>F=BLN&1`mnQwr(jP0V*OzOXV45D7{%4xLQ|Ib(LXf<2<@* z#=I0rBp?eY8(zKr0`sje3g=>t0Ds0h_ksPXynS|J*fn2oA-PvrK2Vjcp-8K&4BEo( zAas#H0m<0jrA->DI$;*bPdZF~N>BB>m-Jv2_>`RAU4_TX)`nX$n7U|0Zz5D~}Rk2f8W%C8znz6zb$dc6>O8jQ2C3BRIa9ExI5)KY|hC+`@HA}nShhChB2+aOpW zdfL-r6om$g$`Sq$@fBgBF0OS+pyp(g4~Z=~8JLIF0^&XqYL=O{38~rmkG%xz)SX2zG?= zM9ehW8Nw69B_Pn`mGj;CdrFlm2r17L#`ojCRo-v$b{xmf}FDvlfoj#(9~IC)q1mG>sDX z_3D`el!tS`j|yw_34$_2!@S>k9*Xwr8QncE zhWW=A-1~+y3VnlSs-tB0AZDPu3vb7i$>?a>y8b_`y#-Vp-L^H_jXMoA?(Xj1xVyW% zJA?#x_uv77Ly$o5;EpUoO92)@1Aq-f8QH_j~=5(S5@!bRkdrcz1Es@ zF7z;()rE*gMr~B-I|+e?5P0o<*g7|xIr=Fw;WMw}=OJy4AVsh(X{$(d)T` zLos186YHZ=c^LV{O$rLP09ZO80>_o~Cq_+uS~bnxPez70M|Gq?#&JvYNQ`J9i4kST zv3MlNQNT+i?1}w5lDOqiUE8LHOb|1|Y`%&p)s0->t}BYk%#My=4z%Q^dO6u%krA6s zOp%9S0a{EyD;hyqN#qVU2PLA$*93Vq=^Thwnl9ZLM_rb{=m#;1M2kz}@Xt4DGAT|J z6!!n@G{=Hzgwhm?1dK&BsLNq$pSCDjEy|79VcwZQ!(ijyZ#U@v6+jbeG>Yf?L$~mm ztj$hTh|tn6V4^`|RS|wnW#c_gCTdqpyQgk7ol~ zl=zKz1{;4ChV!1NQB#tkt67>a>DuLXQ?XHTktIAbT8YpSg(1B+Z3``9D105LTIejP zv|*E4kD;QTCUpj+o?#)ZUr})H{(u(StIomYt)Wv>Oy7OuSdlFR`0Z*JgneLF@#=-T z+I5twEB3d`>&8LF^hRz=S#!^y^bVzcBH1Oo{92IHFt>?im!8P`?nxNxKPM(qyPZVu zJtBqhuyowTq@Q1m@LvsJyJ5@uE{Q!h6KKayNQ^MKdS}~`C@h4N+7C^xbFiWOI;Km* zu*i4bN8zm=fOR{m-e8Agt=^)hK_ppFE{rV4=VI#hwBz{-lS>n!xsU~y2me&&KkrqemRW}H=Wxmy)ere<|bh>H>jSyhTy z60t(aaMB0|jC04^09X?nI%(%{HE%;^hjcAPxqep*bM$Q-0HqXM*B%ZP(-&)f^`Z7(R<<#9>~UEX#J*UVNA?znEV3GU{{5l1SM>=Jo< z6YfA4&_$6H($k^<4sUC)#lUd{gL{Li3ov$$II~TSG!3By=G-%RTByWuY#XV=_9SFI zga9Eyav4f=wk@H8M~&* zJ+%CO(kGiUn@pSSidS;oND_1Fe`T&nyEBbRkI(3(qFjoCBC6S^en&uKmxbHa)Wdhy zTq%=ZO_9Igk-OL1ujs%^wMtkReL++i6AFh;`su#pP4IDF6ctQjAIaO0K)|wUm^M0k zU+WXEsVb%YkUD*q$D1 z`1B;3DqL0fPdN;KRYN_Hw50b`cd7$>yqt9{=Vo7}LQzW8DA0k6ckjY41!me<9g86y zKHIQ*@$HT1)GK$D5B$Lv#W|p9C#6jE&glZKJx*&{?h&Q2R7d8-cPX{=e&Fafwpw7e zv9)%z+nBYa4%uM|qPC;8Y=r#k<&2f#3nR|usC^WrEV@0YhTAec42lAz64QSVTl|(y zOVomkRTY3=MCiLKAs~-sAB(|>ndbe$h-22&Ur}1tCvmq@N9;>n+=26QrfZuG8z@y2 z0xWGV#DGL7)wSVD2h?ZGQB0A-;x&!~mTI!UgqlIg(FRAPiwUwDP*BONlM$MW9q}Yx zrNMXuo0i^njSVp}ocwcwxg5WK8oq_8OO<9a%5x#C{s)NkTDDJ_g7uOCM_48(@mzJ8 z*g}$S+#6;GlTZN}i+2&{wTK1d2C5sTx~qJLjDZ`hxPutc@2miy&S5f)Dc|$o5r!;h z&`@pNEtc14f}=yTSBN|FuVIQ54vd`%J-T6r?>aXOI$Ff!`bC|k+;F3~KNzUPU&bTI@z~oBYgBHK1JCEnWaGyw36RJ(it9xgvx7l4j8k+S zeG_IlfRkcot-jmt<_)(De3!j-V{aa&&7*_T(LhxN5dflb$vBJr;*i$Gn4sTx{%svY z;HX6C+=_6yze6se#!;F?Mm8eCU$!7%(zhlmACSGp#&+Xz8 zRsBjIci|B%en^`jPbO@ANQ*_5G&C28rG@+>J%e()i|0-w&b|!D^jwiJ@ zzI)`=rVDJCk^H0V{iD;CHslDlJKR5iw)U6Bu56Ki;oGb5Gx1=esD|eR84B9Gyw2H`xj_zjT6bPBG zD$f0@cb3`=#5sxu3F>F{J+wdi2^4=#vWNX9yXQVAAXW735N7~IqioK);??`@hK>Xl zG)i17NsSPr_dkfaamU;FZZa}Ww~~diF^+=>JesYAGI&X67$Z z$_NGZ0yRk1%wAqRn!j{Rgic>JEP=S>cbn{ZtU;zH5!IzC#X3LwHl)TT_$6!K>PnXs ze!hX!G(|I}DD-rNJ$t{>o z9p8&%rZ_mhOK_lD$f=~SBC5UB3lu-;4IUuOpCjo^KgPL8QA&o>(S!I+d`F3SMZZ{| zufX2hLG)%{*ZX8Aae6|INqy?x}MEXT~+B zD>SHQNo6aoNayB^Tl2mD5jr^4%BG_t2CYq0O+A+8wT?okNfd_qVpcr5E# znSMiky(RQKj)kv3SsVWK@!FMg&KuAj!nDuriKJ?j1frs>sx!b1R)#OTiWrc%0p%>18=UXS-tFF1n5N=BBCLWLY;#DKBss z`slrWI$=Df{+fWE-_D=h%?@Fai;O z^wmWDcEy;u=$&}UKQnMaodr;Ahkms~`Q--R?4VK1>^28!-KG+QX7wJq(NWTedSj~1 zT=}R**M;7M5#H0!sHdQ*thPu@{IB-avQ5clF-A}1siS8JKvpw_yhBcK3}sVFNCi5Pv&l#rmkyj?qk^I|4Dn>1j0dvN)G&e{JhD}7Qk*EscP zNDq5jiBe=y8RUHr@~Sv}`1A*j5IETi!;Aa0p;B52#prX33cuJ@1dm^x-4{YB&fK#- zyRZD7zNtc)d9bdFo$Coo>2w_Q{Pw2*TNni6MHmVx00`g#C_G?d^BulrjGAYcINH;@lrCz$=A~zU z_e5TF=9kK%`rSmGg(oGBTsK%Hbd%gcwQ^3$Cys_M%FTjvqs}E9!-T!_bHtah_7*fj z?;b$3s;R05qHHbynZnbzaHklQXW4Fve?A%ex1W_-_rHy6QdYnShhUvreo)nZBjl!; zw-7xh-1(1J@$4_$)qlPgA0sf5Ia5D+Z`?w!)sDxCr*G%7)aTD!8Tv(u{Uq^`4M#IE^mUCD z*5Dw3)fQy>gj102wsW&88+kCmWL^Es*6H=`ct}1Aq7ghPiR@Djv#z|Z5S`@>3G5}&OW=Pb(SF~0w>$b> zW_~xQpGs&Dnz!`XC%OoZK{$5gVjAK2!r7M~m4b!i?LaF1G(^xrWfv3l)m9OLvSEz< zhIFU0SOqydiLbF926Ybb31*WAOWe#n!>N+Of)qY=9XXMQS2QLGOQ9GJfe9eMj3|Ka zEjfJSr&m&>+yeclE~M2|c--QPD>Im^2> zU$D*}3+!y6@`*%=f?O5p|0og;Y!Wc;wQl4lj)({?i2BN`TT)O+xIs+VOb=Fhc-$&& z2|JcFC(a-+XI3dSImX&PahPPmudkGp{K)p(tzcQ!P#T*5$y2ZzOZGY^G z*5m(}3f9V&uWq57)ppigY#?iD`HTti?`?^#^scyEuLGt1=vQ8J2ZNlhT4Au40q z^+UMUmyEYe-@kmq9HgL#sWdy_WSJQCM)l{Ipl6mX%%yVTdE;5)x^pluC0Vw`Z^?B4 zr|1x#b2h{}g3iN12ivR2ir3`|iT|ay0cH8Mc7FZCGdQ2+{}d{?iEADA)uLNgoSIxS zM9_w)GcV{zU-=tV+oOSsH+HGXU%%{F$>;g$*YNyYZh4Lu);S5+7x8}n^?Umz=db6z z8g0kz)n%S@P7N!*fKTfp2|>`di1pG{zv;gJefT}WeW%W=?CJ2H z&ps1`k_aFbvE2srl~rPy)eWUtf3el~b56Gx`Ls?VNNb*XA-pNgWYble{7Q%0LBpq; zhqJo0CZFBP0|=g=od~#uLP0~E;(jKc24Ikj(5LaezxS;q^_tIA*sX!tJTS0^NF=8l z?RU>l32vgz%04IWtb8W1+-0I`3V)w7^aO|XO})%3?vWINPAztBxHrRW{=+UE@4Hfs$>}=D;#-DQe0W5W4v~tHYFxI&reTf{-?lpOduF|4Tt&BLagv07cpk=C)|4=?&4sqg4o(h#r z8uC$(cs+k7&ii>yI&vqK3DNN_fmDj<6gBJj=C)|NqI{O8B6IdKFs|GwdNDC386Qn5 zUpQ}yFdrNbCFH9g2|Q9P1^2d4!jQIg9QgfoFP>uUtL;~AKxzWfK66w7#t`E97H~^C zHoqo;o^8MGfF})AxW0WTC9Ui<9zC%oq^brkB_x}_JW6JYGxP@hy=Xk9KtdbI<%?kR zroa9)4^TE{Pg<(DGh9#wl8wWZj?^ZxcMb}REUU6nM%eYXPbDJMf|o&NkjCQ`2BE6w zN$b1uqGTJ6Ri^53$di~Uewx>1#I?M)14(Ts<3u_sWzoT~RfmvZ4oA&q^4x?1E5iz` zN#1-@ErOFdj<6h;dP`AdDH@MmiD4moj)3q}-qAI)u*AxJR%+ynDA`8i4jq*vqB?|y zjZ33lFP9&}k$QGx13wsBiZp2Iga?+xs>M4l+R4Uwf!Is!8*>Uo6mP+e!&gQy3NLci z)M`&Ob~$smdgiM3lrzY0lnQbYZ6QM(3(SUj$;=zeB+jbQ8Q7TVB7*4rrcb(|+Vg(^ zfd0oP9weWLKekH8DBFPiM1EBOe6Gt3$Q7U=#RG6_1*&dbu9goRsw#e4l%R|5b z@0FY*1d%~xT4rzBrqp*(Ljq74E2`!$YnJw_&jss4>jj`e0c=f9CUobkpOet+tX1+* z_{wUz(45iN=v?D$*ut=0(4DXQn8W7KtUnUKHj6pqZ#?bZ1`v_PL?iErPOs<$G9k?w zt>GWpVl*VdRxNUzyiv4g)1*qI27Auyj zuJd82v{OC{4)le>9`wQc<|vmRs64}3Ue;S!$XH9?V|+sCyLn+z{%x*U#}$c2kz$v} zQWrpOczU`;qdRwQCD}Gbi=L|lQpD@%63~d#quN3kplehx)`8XHp1H6M?<&Le z97II#4R9c@l2s_!Q(}Ty!={BKInL$Kw^b+n^$lw>}jH^qv<_8@xC16hA+)1u?TfzwoZ_2~p&ExHrpB_7RC5spNa zrHq&Rv$T|%*kTg-)8m#8at&_>YAt_b)VtOgj8Z3v%pLqcy@sT0GDZm&8wx-iSkYYB zW}n3bsV8WiolM040?PUO&mYmP;uLu8S=a*#CDMzaW4&rEa3_O!WQgvK#O6Du%*H+acG*V?H8exkq$nD2%tS@#_C$aq~w z#Rmecv8SjG=^*8YqDLgvYoW;lwEFi})my)6W~VYkCd*8F{rIJ;@#r2bt*})QMMYJ! z2_1RS!f5qyee~zwGEh;1dkf+S=<)-Mr6I+=!2uJE&0mtRf)=eX>-qHMPNkNa@-d07 zIKb1SI}DyrIRc=Xi3JKbW!~|A3?+i_;$ro@N~Xa=Wtzjla^Csm;aH9hZ+9*~xcE*BzK0~a z(gjT8%tCz09w1mD5yFA@P$e%>hQYzghLaiz_~11NXOVKgO5=g36v^GMRq+k95DGGY zh4YY$%Zs8_sPa;;P+0XNsZ2gj=-5iTP(k=C>e7OHm!^&sz&7~sg^(yiR%BZ$Hb(xm zBmi3hT@o3^7opf30%8^qlcgJc$cF0#&kuk8;bR6Q$}%*1QHnw3WXl+oL>Z#Ql0!Zb zsxmnf5QGO9Hwh3mcx1X<*XqW2OrZL=8l(HauR5md;DHbh93GqZDfFei4W$P>SoE@> z`bB6=EUj?Jm-L^Z1j?}9Co$Z`Hy)Iwc-k~Ho&jLX6(&oxacGP{IJJ_ALs0(6_=PM3O!x{bMlPe3h7A(|MT(Jbma=_75yph$ z0{4#yOS8SOP&S+1Qr_O%K!ZKF9 zlQgFsjN=q*{lR1tF>{XYq5+iji$-@_74DTMs(p_q)KF`f8G>UG;P7d4x;fm6-&il+ z^lG`9UXRL}(7KJgCdFP{5wJC~MY@A0J$=ZIV z0^sxdG5{T8tra)Dksv$ccyOhkE2~ES2p6EZQQ*%|eW7paf5Hb1bfh@j9>tC_nA5*{ z!4AjYc!~d7|4%S0&wA{&e45|x8`BP#xQRsvg!G;&G{!YnFSrd#(_6f3iPuLXL)#lX z)NCR`?e#uj4@zapIs}*%Y+_Xe^V6jMhLoKG@Kb2##M&M)s93%hKpEp+|k{1dOif;Ga7%L zxQ(C?hz$|R-fCROg14RHMfJR8{16{FndR}JSA)<-84rzfTyy=`5Bm2&ZoD;zUrY0z zHM^UImw0Xs)r3=Z2``SxC@g9$rEiv0OjU+)d-@ zgo%+=-_IWZ;|Gt#tL3hm7BWH+mS}PdZsA9fyZvoyDUyf=h^g+DngwUoV%a&X(N>S< z_=NjIBDHs{@ViQIZn;YB1&Go)&e8pW(20)SrJh>PnK!*oanze54h2s?@Y5=gxk!R; z5V@z~zu1BQw^jI0-y9uCZQ$vgOsQFK)lnEyd*wCj$0dY5UoZbHR5ze<_f9(&`j8&H zI%r|$4~8u~|A|J5M{$UV5|v?&c#N50^E`m)SA6 z&k85~j8xIUf|AAh`BfqbkowZfu^j`i7}^J3hryJTfKUabT1vD;JWm=JTi@6>Rmg{i z#UWuLrRqS`{it2)hhuU2lO=2wh91pvdBdMNNMx?xL{!R?8kznA;NHK}uFJC|r-awy z;P67IgKJn%Q#Fbn`!`}x8apo*|7Npn5*kM?j|j$`ZtWd;_yc?3=YPU{(fJj1d;bC$ zbJgiMh)K}wur@Yc%(P`7*w!~&BAz8s53B$6_gA%VBN zD$wGfn#HwmRN{pnmFO}OO#2u_GE7=YTgQqiN~J&YaLP<6qF$kg(o%^n1`e!y89I;? zs?{f=qEyRMaSn6fyieJSXO>{dL{F~*;{;y?*M-+HD6s%Ujd^O_-=Lo!JENnuGVn>3 z&rUI2(NpECU}6%}EusL4O_Yf`c1Uv}6h)@0ndi$YCmLSzA6f^WzIo=z)inYXk@%5u znl+I^aCx4^LAt6EMDAfR2PA|%>iowbGR(LChJu2T1xY~%0}C$lCINPuY4tky-v7!~ zNhvx~vu+@=)J%F8`e)>=|ATCEKI>&0B4TWhG2Kf4wX|SBEx3-z+(ET__}!xJdnXRJir_1DT{bHYgT#Z^4@XHY-#rS1J$#xoy1OP89)zXX%r;}& zmPRbF0!}(LNx`p9r|DN6L?hY9TDY|_DcG|(@!Y4AWN}|(6#UHY%4B-QxIRp6MDv>4 z`!eLB}Dk>FfWP&x7KjBYiKK zlu>_9*7>tX%P34AM6%)}QVUx;gM>uK+TqtZWoq-}I<8)54<}PBv%?=rq#sHac(G8SsT{u4;Vkdo4&~nFUfs9)cZmx_gT)KY z&$+iLD!s?N;Rb4OAt4AMeM7C6S`otd+(CUcu#Ys9BzBSU{X?6U%N~8!@O4XX0lLMc zGR!D$-TwMrET(vDTEg`p3U#8BV_x^yl_?T%l!bWgsQ8ibUKkk;axOA;=N}!9VkK*3 zlA30;R9`NG`X9wDUEbT?cbtM>!^4U(NYPm=X z{w);sfX+kv7QDQmloUp@jxRLkn1#`c%gj{2Ph#RKgU`#p_@N^NokDw@>!#T%+< z;g7TF&t+-KM25qU--vXLW8&D;#qDIi*~m&pz3TAYJ_GLZrPt9%U;y#GnI(?vF$VJ_ zBFRukx6 zKiy00N$aWMIEF+|cvC2K){DS|y6XYa4RpL>^{RBBV4j8cRWtwoum%N|bZG83*^8RW z#B7c9fCtbRY1%-!IlXy0!GINUALLe1!bSwr3 z+`FO>3BM7Qf+CLxAE*xU8j601jR4!nCcHJPG!`1ifkUd+@TYMB5W+Kz^03vwe$+h} zQb2zwqoYkpgID&gBkQ%?X&@LZp!0jO)~3dXaUgR`tRhxQhcYf&o7L8IMVs)HvRlaq zi1QIqH+~}6EO|N+Wl`)L>66KwjIVlhpHxEc>)U_c*PlW3?f5eYCYr=V{48rglG%KO zn1vebUxl`q+=w~h<9)m4zc>Q2MaIeg#|<73xME#;6s96&RyehNxDWs$@c&~AstL#2 zq{_#9vKkMw<%@Zy!~B^c0miH9p`qVUJovjOwV9;$B-7qCad*yh7$G)l znmrEXhI^%#8rw{70{Mqtd*=jv|LTo_=ecew3?*Ds6kigyzK3~*=%7iJ8uA`v{^taU&n5S4~FRJH?AF;;cw2e-ok zf>0pQ@fQPyS76ZO2?RJm&mwUjUGR|BYWnO_;*f@O-Q^k6^<9uRVWh!QXaTe7W)D$TU2c@*Dv10)4PfswXUyvXrk}d$JDRH6ny#NR z6e=W03pEzVr~F0%<-tYwu3wA0xV9Bjo-E`~Vjz}}a-#zMJpl16c=i5;(LEfODzFBp z-E3|N$T}^eC{3GjoHMxOT`4UmvU*AJX)Q^u2|Nl@84BzrdCsY+rs@JcDV$O_oe$A8 zYe5K;tcF^}mV7YYnlA9CS74Ydn=ky}+Vf?eC#<`AaMnE(fkSChW^fJ zH^Qn_m-K3eUEsFd$ha*`T7wKAERIIaf{c#&k?R+Aw@8>k`4b<;TkA8#MmTY#r^)j<9%=$WWR8RnE}DHx3lr z+r-CrUVd-N&)3hu5@VQN=fN9>zlB%sJlmTfWNbW$_RHxzGpdR!eNcIC7y??778|An zEq^8xS^N1;=h&_-GJZEl6KOOq{{g|&d`grm^LQG5sna?o8XSVR8WMuXJ9f%9{v`0q zr3!zz`1tAu+(lT2KTmW?5H{)9eB;xJx@hVqw{iL-;8@-UOeDlpFgW)cw4Uy$b9X&J zmu{y@X4h1pv7Af?KH&tO5RW3+)A8v18$%-Mt#u#%6y1P`Rw0qzb#)#&YZY+pwl&xQ zh=J2o?Ci6jXQpIE{7bCN13SeO6F>#pN6$E5qR~;7sw2HCz+}9ui8-reP0XpgNa)xM zS`;<)L{U@E{k};~0xWsIhaa$2)TkIs=M?L>1>|UYZ=7-oq)0%+yD6K44A3WV7f?26 zZJO|g66-mlNMNt^_#1P9@0*2u^wsMTT(`IwwN~pr0yo1FD&S%pGs3JfIzFq#_F-Xs z-6RRC`80=(sB1&XZ$6uXCY?=(#U{g`cSRdB<8Bz0?}fpKHbTVdB2u3#C(%vzMz zwUFA+>NDI=fE_~;xHW)KKB!zhiTE(C?Leb_8Jl&6+_X^z7q5piVcvm?&Z5YW{1j((dS@_kc(#3176+H%u0O8S9XID{^=O02LBNt)Ib5Q@W}dw?pk)j4CMg;->U! zaUCz5UA3^IyAM1$#^)8#)zMF?IT3G0t^1r6(-bz-j^DzK4P6CrD)s14-iaIXcNZ04^moTaYp-N+I*g<8CxOE^TNn+3P0 zuYCM%i6)ejQy7AsxoakUfjG6($=fgZe<!ZnGc+Cc{vu)oD- zRimU4dt@2q&@{gK(OXN3q9&ZwR+@aBG+q%%a_WW?Dya4>8KF3TRH-OAJ4 zaO~s^l^w1Mu_!bX<9JuLq|qB{!_+mGdUHmxhG_)X8}N34A4+0*%Ht#Kho%{oiVa z(G34^7=sjO_Fo!jU+UooLe}EFKYpaSE5tm-kD*no=2zC9v~e<*=M7K>AZ-b$nL8Oc zQAQ$toP}|nIUJ|hKvJ%fVX~JDkBTSkGQ?YXqMtW1B3$-0X0U}p;B0WAy&W@pgL)NA_@sd;V?ZZr;$jA$E}O(Eo}s49HJT@!7|(Z<$O` zG(Rjj;L+sq+;->|=>=(JwH@}BF@C~w)}Z#5)y**UmVmK4f=p{<`Zlhq{Cy=BLmAeM z8_Qj~n~5kVUv*pA48W?5$HTT5rR{!4NA+2ApVlIHqOfe8#x~Z?GWwRxMsmEIConH6 z@rZr{P+h-z8v#zQpSm>z%#P*jW*&{9X&CqMYvpz9_$4!o2OUiF@~= zonC%I({r&n!C!#bKXC#tqfHaCHjM^Qr3);NT5GjK;Br~Gl%v_4 zOhV(LW&{feRpy3=g-RK)GBMDlc^xC|6yGsu#!z`$qQ$#Wz1JqvjG}n=7eEoSPg4+K zQE*&AJ{rieS`+fa+I>V;nc~A9DTHvYggNaK$QHafh5{N#57qL2JF2K6^oY{lvO~@B zDDeXg62awp4f2$P2lqdjjo-2k@m;5F7sc`qO@3S|3vYl|9Id(TGNtvmiHlyDSS!3a z18#884JHxmSue{e6_llMpJ<=u{TOyrkTg>KvW7f#>LhPV-}6iA1WaWS1n)gvKKLfX z?`ZE98{qgJFzu-i2k2LqSoEtkQB-N0wB>JmOb%n9F zIV2Zc5J}y1B7ge`TfGF z7q)Kwi<|1=num_5gv4#o_n=)$&KsESjakn_X-Yx!H7C5>3A1U9$LW`CK<12A=exx> z&sg(TyY&Nt9q(DKN+6GsFPHoZqh}R3&VnZ)5%gWU1JIn0|AZZl%y-lqz~QeHod>w@ ze*p%AhyRFTLA?XfuR^a3zoMfiMx|x_#A5Bbwdmj;oY=Cx;P%hyQeLBT!{Lw3`yV&h z#rtNIbWtz)8K;EJmTvvZvim>$;J-9EhB*9QO&%vzHuv?&tlRK|r(h4sY7F#t-*m5i zL*Dv4u}s31jO9dXXM<*PGu*j*V-OR>Z^~2l2AwJ^f0F+s^@GpBlq}xM z*we;B!oe5ArA7-L~@TD4{xQl57Lq(e}T@cffx$i>rqO6l_^4rsX6< zdG7ZM`DLv(hseS;A4WKOwmu3re-BgX2#sRPzXb6;qrT zD$xvw6w&tZoRFQz)RMahdCw?L2#Or2Y8Gpuvqe;UZ!VeJP(3=#R)BsAC>ZO@l{QYB zct2{N;GIWj{chg!AR)Ahi9boYGgME^1|qWU)ta&y!m$9#*{-Z5lDMlz1uqZ=jKDNX>Vb{O^z0dm7F zECM=}*iSYNGwjfr!pYTbpCly5J|fr^Gy?wD*Ii%WIG74*Qn*e9w&C3ei4mcjxuj)B z1RK_6V9Ra*2EbpO#D~4;h;0NMw$}Zr9kJ3VWy_)85;x^I%sDYBPZ7`vS9wBxY3NZh z1wESYKwODTHD>naL&NT)_QVV%igWiY1&K+ z)E;*Z^MS;^uJDgM48^s)k6*o1K^mk~h0vq(Uk9tpGEl@eiYDjN_cG&2$b+FLgXU#{ zg@i>ZQHqbQfFlZ;iNu-_fE~6lgo%*A!TbtVGt%2}ij3_m}ArX7kw5 zqM|v*_mxN32`YdSfLQVWx)4S~<4^5aQZzw{rk%vfS4EITstBqwvC#iP-A^G`UN-d; zt0_lkvAA|+Op&zQ-hW$p1V=`rmtiX@=Gz_VZ};kajg4IVdaeNQ+2_6)5C z^S1-;cg63bUF;Uui%m&izOTTZcHXHy3O(;NO`VB9OLhP9BweskuK`YXb+_9=fK#i{ zW)AI1Me~E|)b``$-BV8fuZo1eDPH{r(7HWayb|~(|M+<*_%cn@>7e%dyV`lMYkgaN zRoO#yy_#LQ;S2raV;rS1v4UDI6FbuvcxR?l6zc-H>o=fY&p#~w#D+<~)hrp=rA zr<#Q|*H?zge*psTMTdf~VuCSWFzreqVrdtmLvL)2{sQzvcNNy@`~^5z_rArwhMLsB z07#GQO$$PQ0iNwzDxm$U1>fHW861TC1$Y^IB-<*h)sRYK_5rEzU-SMM6qPA>BpVj4 z@14H}P@%9D3urucITw7F4Ul|}m9NzaVZvNkAkonV`}d=?gy5P03pP!$CVBf}yxBy@ z_d#*|QrKT#{d4u ztQabserS~M$4XnA!9FuUNNSde9wksemWu<(C<0IhB2cJ=@7@1Zc?w5&FJSN(2^XQ1 zIk#1Kvfg|&4vUfe?Z45dqHMXoU~tE)Mp*Z|49bB7|L$XIBLAkULn`Re;^!u=-Y3}C zv^x{L=8x>bfPy`OZd%2(Q{zLRSp9FmHze_aVID<6&UNG0VI$#k8F^>0fFQ^v7n^#Y% zf5XxavJ`^J{rQ(%-p)`nf*?e|j)h2F&<-Q6e=dH0qFE z^hPKvsoUV~cNG{3s5%wGsbDisl->eN8dcz&M6KOk0k9x(!4oo^FSIi4jd(R~6OF4= zqjwn;s~_gHk*Bpu@+wg!(n-L#hWjSe&lch{WP9%MfCrT}M-`Q?*(8gHRfE zl%AI>8?^CJHQpmGbTO_dM8!yvuLdA3ZFPC|+ZY~tLiD*F;=&@(fCats^RS+N5NZKu zE+N%H6s{Ys4z(N|Pj<);Bcv8Z>;9hDaXcUn>HAzCX+Nywce012w;Z&p#l6;4RyisE&J2S*! zr%0LDHvOMikzyHORj%v^07JE0tmaGT#eKzZ{pbRO@_7Mx$-GCyvBro% z$gi@>7a6t7?NQOyiIHeD8&$|wZ{?;=B`a<|@2ZH{RkTi6J}mb|i~fiI1W@lJLgJBZ z(%b)BFUgH->V|Rm0Yt+`DO4<3=j{q#(BTCZR3?AL^e7-Q)B(@K=&1;{>Lz#dVF14B z`-Yt7wC;(=_`N`@B;p{??dPwJtaG z@GnGPqnB{CWaqnrt92Z4Ns0t{Y`9@LDAPA3~bjZ4`joq+WUZ zn5JIRGVBhq+Y0C~J|>_{C76_ApT6%CXAt=7*_dC%*1Ze&EJsD3F9H6MOBU~6*)k?> zX$OrnHhrmkqU8%y1RNR|5|KBXd^TRFHLaGo;Yo@T+$Q+qI*a@9%nt#hMpJlSa~0$~ z1PGCO?^Il_)Pj%eqbusxT=3aApdS!%fGw0%gl!4lfa0~}(>u`p;`;04^IiK@n@ILJ z=nLR*X;~pH4)w+(ryD#K=DipcN#F3(!|(1s`3vBU6z)gmYVBTWzl|203-YpZ3J%n` zEURXpjXUcVI7(iXs_D1RTYBZ&hl~BVgF1zFu*{RORu!hp#QeQe+_*9<8dlRR_{4gY zKiY%#7+&QAV=+rqwM4GT&L@5I5Uclc`|h&dvczGdR0=iKFOlvxlvEZ_`r()!tg7-b zdcAbGuT19lECKdxriAim_7=48p}}dC&utJO6_^*-^@a{;Be&hK;?f5dgf(lZ+ipp%z3quWO0ZW9FoCyJ z$g=&)CIrqJ&c;^@POyJCzh-GVL+NeVSClX2oYBN-F$OQH#0sy#w_1o2bA+AJ4Ftegum+s33Gd9(6zc5+w z#r=G(SauZI+3HY)3IGgWX$)3tBf(S9+9Rno!-1!?L6#LC84N3nP;~(k2i0rJ5k?gMTh&gYJQh0^qE~15ZPjXZQz;bs|TzY3z&aSeP ze`hNLP_Eoz@5FJkGxU`(U|A71)yg$2g4$TTt{5q`ID})xyr_P=pL`V|k5*1qi*`7y zVN5S{Q6KhHq?a;*5a2QbNl3Fg%)ygIn3_0PAHt6JWpt8$JfqZWsqYTMvc`l-Ip9R7 z4TW(rjFT0&v?*~kp-8A5pQZO%Gh~X3p5)C1QRG;WhS$X}n9K<=@9uqgviSjo0rJDF z+aj&~z(=^F_v2MoH@Al9m6S7$OK&XsYRT-1wVAv5ssSCV$;`8^=jT^g=bmOFV>*VU ztTieph>B=4NP@orZD2n?b+z+&FkJ|$F0F*a$_kS!#OT9LF5gKMu z^ptVlK^n6Asc=?@tP4wb!YQMad=2jq-UG&wo#mGkjk4tb##CF1daTG#h7~i#&QKx# z`O~u{`PAuRP;-3UT*g8QU}9dlT!;)phGO%R4NH^u8Tz641QC+J%S#rrh~nyDnL;wu z-j;AEktuD@>R4>2G&?_W-UF5g$C`uS7P<-Tz@GixtBB=GLBD8y-d+&@r8KW>qY z;uy{zuWNd5_2y)n-p}_%Vd$%-dLFU&V+{B^8P^nlup0IdZWx+yI=iCe=z~Kuc282X zM&E4L&V77~?ZJkg`F0$*%E&fLitqa05?gLH=K`0^&SLS zC1p9AJAVOEt{{19_wbq@K?JmpOwpUG5ByrOEvlI7h@P&2WQs0jwtF+h;~v4E;><*E zi4A@M+qJ^~}Rxjf(V?Pnk@ZSDDbCkUQ zK~d_hB5duMrEN6LPW3N9DpA%;Bhg6RvW#P^;|>i4I8q3SYgl8~HIRF**%>kd{VQx}inLg)OB=@@!03{Mw9 zE``*>l&c%hEj(pN9p6Nwxsymvtv6mvb<`l6_u4AbRt#U_?Usiw@Og5|hA=_8*~_8N zq)9__F{v;n6x>8z3`Xk}r_i;%v;;R={K^pwhwPNL^&GQCp4j5YCg}o684dG>1K~pu zKxp^OvsgB#RZfz?!LY@=R*gFa*Y{eAQ zno$2bAd*S5B#cc-Rc_;y8^}z^eq#l+Ne0UecOD`E8KkAB_Js5k`>2GJk;yKRiC9*4 z*r0+>7dG;rdyIBvJJpN3871)eQN%;bV`C|wcBYafJg0J_z}K8b#d^N4>C3AXh9%}| z8o&U-U|^L3A<+E74csV;1FJ#x$LlwZX7W%aE;XT;+^H0%N`4&iK=JCQ+z#krFGHn8 z;@jmvCTcUu>n?gd^Q?Y@~SuPcOjB)1$6{^3i^uy_ZZN14DVc=&}6sp|= zI*q4?8bGRQ@lxb=*_^`VWxm&0SgU(Ym_2%;i6Pv>-6+ga8d0v7_CmyzeGn_ckg+J# z4X>9^_sotCOiHPQ8S*?--Q04h*ej{80Wd`&Ao^L71a+pQ!ssQPE82m@D$ESgMyM(dYx-cjQc`*dFt*Q%@i@o8g*_)8lAlV>uo?ClqPnGtbENL{|*ID};sL)i9o+2`{ zFkb4luFrHBtYc9j6~R`*{WNhZ zNndN?i*wt#6yk8shJn@Jjk7b5$316^OC<|SfL=W*%u_^;tVBH}>R~q8CNyAAQEZt~ zA+Pls>PQD|iJjQK8Nsg<;|A3<5+$y25<5(74wVboh;J9s8__&NRkRhH$v)uhYsjL< z7d3ISl{}GAt&e*&ztcx^X2J181*e>eq-kovEUOWzKRdp0r@9SFxF(&I(Qj}sHy%iP zy((F)5k(r2C2Y1Qcq$q=D|&c3l)Oz8bWndcLhViUV)c0B=!JBAeB#@0 zK_l-SIee&g!h$wO+A%Cb1ORA_s_~A;?2!W~Lj{*fWz`~88sxBly1fF1GbLU76!MLn ze#G(8E~fo+6OyMZs-gv9Xtv|JYLkj6bPOzF2nstxCBH6vO;QsM)F!G3Wk4pq1XGtO zemFEHKAGx;5x+l4wy)Hsg-dU-utvOC2<1Fr{g@q06lAoIb4u~9HgK)>#7y{+wZ(!~ zl=QSQxpL!9i@XH5KcSB6?Lz7}OXdKiM8BR#VteXU@qYCvlv4XGYPAh+Nknnv6aB5a zH4?JbA71!MH~V3DK4-Dz zFQ;W{x(1|)C;-G&Lfo=nyE5<*TgOwE7JR8;8M~_MEOWy&p8DI#VrbO)GK>fl@f)BX%gMLi}A#E^3dj=E- z7ZA}QRodJB3?nF4eCvcm8%5WuR)l&qYg>g!p7cF?j#ydVbe|Nk!R(5Gp7W{jDN zvz`Gu63p0nk~|K8ijB&f006|cHX6|LA}6y$-!CcIvlEuRDRz9GK;+HlVTi}khqcqI z^GIKvC4F&<(W9IqsfI&WWH zab(1PP=p^(U2qE65)$f?1tvRyWSHf%A4wzOaJ`fo%HjLIthW<=iO`DjO4vE_p}N-j z*qD;d_5p5UjU_Yy@WlFx;-=eqx8Fat$8GMeJxl%|!sc-g&-9(Tu)~`VB_=LHnY=M6 z&KOXFAv1{Us4(V?yCKcN<*T7UG{bY{g6dagHZ=ti3cTI{jYzP?_eWSL(uL?~86*~G zU@XyirgVen3F2AQY9V21?1IPoUc7!(g^rs0m`yr66g69Si9Ev6)Zw3HFyhIYI+8jP zJMWC|X}8QAJI(zN8Z18_AE6=FznU8J&#P*V-bOLs=TGM=&2ikj#G zkH6pu4%WfM3w0(hk-SSjLrQja4b)_ttOpwvpFgV|FvDov?gpd9n${&gE*V)# zWp2Wlfsz2umBa=rV4;F;$UO5?8{ zc+}ZizU1RayD2>Ts+U`~7o7RFB5&*7F7sPN-kFB|BV*omA^k_V5`EX7KVR8MSAS1R zw{qdQ{L2g5K=)sJcYxWS`ZOj8m0p`&MS#Lfp-|?L-2iVGy57>;WkCX_p@9VC(jfn9 zCT&0m&800E0EfW*bNVc~%Lh~FR9FOq$*PNHiYu(_en`(!u*gRZzEB4*kHw}tHt`yq zpn-WCi?s8du1o|WE zpub^>Db(W4>2CCqTPzvnKpHq2tDKB(G$eVj|5tSNc zE{Sp)eLs#{hxmOk675ANwM zmcHEJ2wUphwgq_9YxmVkyX$FVmvP0oXljlAkYXqHA_Jo*6Nno*c(4Nt!(8b-<&%e( z&`etq&CNe~K0-AjJe*wfw@~?nO!Q+CL>hHaDdcv_iv5^arpx$?-Ex%bB>_1+m?G*R| zrw$#TcRtTnXcOhukd+?dw_KJy!@yvJteKb|@slUbQQ6#aqPNm*SgLiP;V^|MI8&K9 z1aI}B`7&4@ScBMZMD35zzBgMI>60n@wJ;4Z387azZ;M!;h`rCnl>tBhngj z;#0BKD*~x;p6qEps0kt&y&boAP#RdD7aojt__lRDRFqvIZ2*k?=@qF{o^ItZJEiFEE<#?$JC!cRYeJONr7nO^MNIXC|BKpGHeKV5Q*r4-=tb5|&g+TmQ&As#PyJni%?Os!aM*c!mgSoPW{_P2- zvSFubAd>wXFS2F;um1J^Lc=b5B%%yt-rlUr1(Ke zv!~yhL}deA=ia?hVb^`(U?Bd-t9Vf1HcRi1vfv=j-}w$I{j8t5LG}7AT|T^YQS1%} z?a0mgERM2d(~JJn&(LJr++A<S!Dd{z{r(uoP=)*IAmi9843yY{yC;Tal?LF~}$YGmF$ z>Jx}uM%^U4z^8tMI6PA_=VPDOK_*RCg#ZkM7IAELG3w3tJ-y&3Z{Mkrj>KxKPvsM_ zxO9_#a10*`>YPF?=W-@}PMyyLIGM z6+Y^0`%HX_(g2vQ?dk1G{W*RPC&Fb2!H8mF9jZ^U6Y|J7!wpKQr#E0oBf({&QhqnP>Fg9gAP z6bkgy#Y*>-N5X(=i;J|0q$tRFWyOYX!%!N?S*rzz#)P*s2Au()+?UsXI`u1l^RSYQ zOVa<4)CO(uWIa-gXjS#%22jnn%YQC&&Zi z<(1rn_q(-lP4L+iv($~%3x%ie3fV;(r2+$-xEnOV8>$PhQEItsEeQ{Kr@0Nz@PBMi zbJ}$T*gydQY~aG-(O)xEdD-*JO$Oig8$gUYMloWpKDWuQWbeuA%zjx69MA{um2dJ4yfOk90J< z`2ltnmRo*UgaL|Xt0i3K4aBRf=C2)?LP$#{IuN2_NjJ2ljwT%kf`q46mbD4dc7c7v z_3XQP)`{oZtj3ltCC0Mpm77LKeZ0+T0lxqqPyI~ywFag3pSK4>e^C`AzwavcuGgO*M;vMe`|zW-oxJ^F)!rDfr#Fl zU?hz;@UE$45bzhkcD9g5$u4~5zLD4O9?RJG?fK}>3(13wTgV>3&va!3tK~guS&vsv z8vK3?$R>d}XS$)avZFqD1_nMmqqfhq!-fG-NNvh97*}WFfLxpKG>nW?wc3q?< zfeKVaCmgbS)8x|E+UxSHa{tVa7 z_!Pb&`Re~y>GQuW0Iim62$L?V$yC6r%!hvYR0I#8DNIGbIA>cuFL9-K=#Ch#e!wZn zs?L1!=M#C}uc3dAUEO}x4_D-$E)2Ms#pUA$|IgwFUJ%@>@0lL4XX^x zrai(=KUlQn8FWKcNHBM?nFR+&gFm1Xh8Wx4@Finwip0%Nx_#S|Mz0>uIjfg%7=&P0 zc)6p3uSfoSW47ytdFiM+J(b!@`$g8!1#7cmAlrZ8^2sIhEvjUe0qT2FKNGX%q zTA2k(9m@Qt_vpmnX$YIi(LC)_^5V8%0N_D3AOdb~LL>;{^rN(gx=xG7?uN1 z*T8MY!6gagmZN%3le~8Vb2HCfS(r2*JFHvbY8BU1*WFfPF?1o3%DwA|XFMtGD7FX) zrG;+M>t>gkNY2^y08jzIF~_Ht+)FyKilt;-Z|7PfX58Z=BH4x2CPN^CCr2lT`V<&d>RsK9FHI(0E1rj- zr>5pSisLBzdi&3TshIDsAM0kBtyLQ(r}x0H3d6iL+V{90ca8eOI6sYw7A6|&J(q}l zr0o~{h^HuWbu1DNAfiqz8+?m2p3ohQX_ctjSrGs7^-H^P(i;zy%vm1_!{O`V%eT?f z&qUj`IJ83-U}+^esFo&}cv{Li;~C@}?J1(RG}vV(lux@*WTasWSlSilc_vqu_h z(h(p}Wz$i)2IhI0h-#UCbf*)4{{{Hx9Cr|WZ7Z1}4PnoT!4k1t)O}G56h@9D3Sz{_ zf8&XPinKo0f`l!Nx9Rmo;=v1QGfIJd&y{h=;RHE^yt707QEw414Bzu!jzU(EDF`Y5&yccRE5PqyYAb^T`h z$N&`ajazndpFvJ0;VpjS=28OFMNC+ShWuCQMxZel0r7z(KT%0K$z$jpv#mUlIPxg` zr0|lA|LwEz5%?p;ILt|L(VKCgwI-f6hHg8GQm;};(S&@2n+^XoLcUvTOBO~rPqrjY zADTyx)C<%Mr9gu68NJD+7w02HoBZ)^Ji5J z3ZM5)G9mNvP}cstOe#J78V-5S)<;Kevi?>mX+Fh#)}_4>K*@h5`!3Vs-;w&BHIkH-*VgN6fhNjfXYcX;n~ zu?Rl92w1f-J9n?D-&a1gRT4O`Uej;`iRF16}60^&$G zWk5x-hH7GSKN9JBIOp0ZE|5_P@S7JXpz%WZT==L$PddeRRn9Q=rfcruA00_v2}iMvs^2fwIbsHH!-b z$buK5cZW0doZ4m;M$W^xQQ&aA3X*#T80n5orEo76bkGk5t4uk31*$4>1$-QehF4kd zwaV#X8sRw+T8>g}ixob4GtFsnI{xYiSUUh7>Saq!(jtS<0ElK_Y|?s-QBYcDRg~jJ zQS0Ob-M(`mlq2%(;Fd!8p3jRK0LrQJ63do-EDDMN9xJ|etjbVgV>c5qwKrM(qzq4l zOw41s?MGZ`B@XZ5^h|?R*1XDa5M*;3xd5*g>{7MDG?RfQtQWx-x`$~$UmMx%%V1>^ z(5ECwsXK4UuUDs#88b)BRQ}p!Goela%^>gG`oijZ;EcWk={pjQ^~Brrc=W?UshoKn z5`0=q{0*V<#Dr@e$Z7*z7Ll2~WW{BBk@=j=GAK-qv^2~Bwt~q;Ch!&c))W~qfiWz? zp+C4^iA+36M5F>-ed@M#qqTyg_Aa2R-v? z+%D{zD%`Owhd0a-Lm1OEQf4XNTA8Mi)QzQJt1^(`EEKOyhJv+R?t#L+j;?)MUG?N- zpK{bWIW1{%C)>$CU`coOW!)DtV55qH&~=vD0qQ$(dH>(R>1R%9H`~qA= zuMJKJd>+2~9Si|?lN%bjnF3A;mMg^VW)h)>B*UL>X6 zIFqVWk!d_+2TI{7k?K0bzhFq^%gW_v&COl|WQ-CZpBOSIN4gPb3>IW_ z{q1YcL!2CpEXP~A-flj01~q$i2ot1z{QUWA&o4mp{khF%dv}-1?4Q5%%}6Z;4R^n$ ziPW&nUkfh|9=$c056J(p;`DvEJ>zEb^z`{7l~wnj)**zkvwTCEB5+64u&%q2KR`3- zlCRu*%HYr)7i0S6C9P$~vG7I4N4G-{OU!dRBjj{5w5g5Q0_* z)EsU5;sAHg6M8W`zP)?#<(uyhiC`KjT-xZQ|FJ=U{L!ntl}@`EHM}s$<-z~>-M{tr zc*kl{sx)g`Q3$RAh!~` z{1qArOBlNhFd#C91mi6q?#1v|I(%W+UA*lpm z>D63_=pL<)D$G|myeU=so0p!C@@Ah%kbEMsbJ4laQWn?)IJ!Lgdx8l)qL-8P0hBog z*6y{=2kRb^7!$ucdNsjuy^Rkju=Kl8rPmr%{&)ZwD(C3~t_mq!+o|ut6}#6`8XjFV z98ItrrdQ>2`_GwNs|^v)6sMBhS*XY3gpe4tgvCWfs8kD=dR_nc5Aw_ZRjK)(nw;^~ zX|IyoY(SY4Y-c}izh0+88^3;B{rY@-rU{IPU60KUVSggBjEEi8Lx@VMjp^7>%u|Vm zuYQhBy1v)6EX7jb{<1vo>D*p?>zR8O`1gk<{0!uew;Tj9PN66k?@-eL#8Kb;2eD8K zjd=KVl6d(C)=rn!;X9&2?Md*8KJ zS!7`(A(5bcBDy39G3VAOTXart6Rda{bCfD@5R(4`*Tyz=TwEf5%lp~B(*3iPXBR4< zY-&^KL5a~uP^5U$bhkIjO@F|8o46lqufTNMTwJMmh!}zfR-7Fi(pB~l@JW%+&Ohmy z5d2ACpL$*FSS)a{p=Q|ZU+3TV@IoM35_-%R-tyk$Z0%wD=5Ls<-1O=6-M;^RMe4%y z(T!ku0I%6cBKf&9(+74}Eq<##ryspt|Hp>Nd&waPV@uf2SC(Ml%Kzid5j^}BSq_yB z-L!~ICl$EmYxDZj)7P5gAF}Sw)3BRhxeH&tfi{e9J)+*vTSO4GA);g|Jt254O!E>W z!S?vu1>yr9U^G-Sa+#7)87C+9kwtp6a>ZsXIs{S!XoR5AI4c){X1ude;{dmE7hqQUL4Fdm%gtNal zGVRQ?Ve?o~gyXu?@e%wF4sX!lb-FY@zynN|z$N52Luex1pY_l8>A%RKpG>JDHF>%F z$xV(807F;qg8#0UJ}#PrEAw`~O2`8I6UES7&$!K4-n}H&85XK4sicErIB+JDpesXp zYl~PIa?6h`Z9k8=pjZW=5{ zl-dB-{)O+JM++4i`TuKfoP0V@gHvca{lf3MRNrlqImv_mklm!cK~)ygX636!?%zn#yDv9uH?Nl#MoYhJ-LCUJWBl0-vY_qHP;upxg(*~k~IJol!aHQuK zlay!SP9pK|0!cYA!%^~xhujKFQyI$7N#41eVo)*x*iM~&HLyYG;L+Y7*h^Vc}NtvjfUm4+6@SwT8!3CK$F)kk99BKd5bflrfToUPZz zUT|gEhpMd%Q_&L(rX#ndhDTXY5Aas7nh$*^)>4y_`k?&_@Ho8uuVRcoNCH-LiDDK> zVIUGTO8XuXfm$L!LM3Y83u`vF5J_Sr{Ks3QHYVtD@tC(=_vzpS_8+ z=D`s2uuI2R+w7r4Xfa!fE+Wj{q=6u9#& ztbx|=`QK$*co95(rIPyl7>ta*3~u`CB>cI70O}`v-^N(;;W6o*`t4}-4pK{T6W6up@2qxlP2jkONe9Uur?k~^j%YfO+g~wD)+o=b@YQyoIj9rbqP8r0*j$p!6nHo~`c6e** zs_B$!?*E#@JV}o|#GLmdhfPFYU~)O_tIt&-1%o^tm&FVcNzR0YOjLF}y5Z_$DDA4p ztI;L8LxV_q`y~XNgI3nRSyJWZC>c%%eiJE1|0^uFT+(F%R&hU$vcU*dy*WuQg zZeje?kT6$ht$-qq2}T%j1b8FgcG1yq}OViFAu>Rb(=Hq6SYZA_WP2yO&mHrA2ZkCojI@ANE5@>uEvO#ikVDbLU zJ6JVT z_E~u7q|1YZUgEd{r=787k-(374ZW8N8dUE&0?Fh{E#7ZPKjHP>j_Zht+WD#k&ejeh z`uJtwTN$s6X$l`HIUH#qxG*0-3`Lyk#jKWOsc2!Zl?X;35Av7&w2h2R<~O}hhByy1 zaeccLY51G;vr=aCKSu$!XkGLEK=~xJli$a4;39~4(83?Gj8p%#V{~z*30pk-bV}cj z7;hKfQ^$@uG)E#MaADR@67?`@9B_&Ilf&Q+6ynQ#!wdYH4B(9g@hB$dEZsp+3_Ct{ zpatXcWv+SKxk}1+e0CCkoD65hxy%bZ(XTjKD@iN*3v~jM^Svn*aE`EnkFQHI%@zn{ zm%nXL5rBbMgjTZc15|igVYzub3OQ*ly-Wo~$B*#uG1e$&B(bgN2+EmV^M&b)*tBw7 z0oHP}1bUbE+Rae!HC0`0T*wrEv zbPu<&zfMRdX^+FX;L&8D89APjBu#srfhA-81+h=E>xk`GWmW?8u|2yj-?wgxeqkO( z#dWFDS?sai~XU)0l z*{7ZPuQp5RvpbMzPL=Oyuvp02?7vU`ZY+x1f$VYjTz7*B1^d9X2FXa)(V0a0#%*EqBr`i#wxKVS zWEHVvCs;_ak%Q$3!So^E%uU=jpKtaAkFlTs_vH)Dcy z;869gCLxK~UGi1?>3~m8$5~)_m|Y~BIY1kb$(zCmOJst=w^!^U7_*n&yC@Hd!uHgj zAppM0TQWe(2F@rNLOblbiYzEf08-0UBw&= zcWh$;(#;3Jm>*AIft1`Oba=wM|-$N4m_@(@!p745{hpQKUGw<9BwM4Y0QG zU8w#7%=@Nxpy)P!>{w?(Cl+IL!;&fV8N5E?e5bJ@`dZ`N1qR;yNqD#x9iGS-_k@`s zrFs=FIuSx)V{b$rh&-YujcNxkt*mwN)}u37$OmZBrpGsKW9O_a+29oMFh)L5I$39b z(m&r_+Vb)q@KOh_!U}%@Jf%G_<_zco(E*udlXA}O8lue5v#rO6@`Gv<=Cj7A&tVZU zqQDL?aDW=uE2;(@wL>DOQp5K?`z5?Z2#OXSL4ljIu|lCn%s}LzYf*d1$XWXB5sjGt{O#MY6 zjPSQzJP#K76MgSet0<#I?*QF*wK**f&aXFPhRPQ;pRHf58r|SPShp=TOzPim1L)^%CkPk&)YMHq44Fb3MmS4 zkThRz1u8F{!zA`%77da|jltu0a@(j=rA!Xo&ErtM467KRl&oVSvhP6m*8(STZ(g{XnHJcF}^l$BIF<-P5xkZ zpoYAzqHGH~#A;`LzJoLnZ7jj%IvdCHWN|noI%PP z(e}Jg#kYbs5wi>^C#STX3joN`wT2EeG-INZF1PhfY28arK%lGF`}#LZW@JxUIqW}L z7F0%zf*}Mtkr*p1IJj1?MJb;Vz_>YO9x90W*?=HJ>>;Ay*gxUFTb!t1UONAnM3X%x zvmiu4Ct2j8CDgdLc;F%K$~}g;$wf5Av+si)_PQ0rx3} z%+`&+>SJtltanKI=y1Mtv{NXfg>X=yUWlvi_P2q|Dm;`yg@~XynUBhV6Xhp{bZTG| z*eyh`ky|tF7?r|MkfXL+Qi>$CJoX8{5X|e6D}!^7m`v<7sb!WH{WK|2!%|G9-#rmy zg2WgTL>j5CSgdbe0fn+qn`vA>;EI_NjBHD8J|q_|8DXHFz>u?max{d-FRsRd-cJBO zH8O$XPBJ1YeBKQ~8*Oh?XT0Z+4MLzN)ZUjmS9;{YIP&&l@G6a+6{rc2(i7Rexq=j2} zCLO|uQnbLk@Wc7BJrLDhw}s56AFH+{1dz+de2JUt0kgyL<3pSwG%>U0Cfh9@O00Jm zMOat(a@wW;s?>z;kmtU_gjNMQ2j%5NBh{4>%kIMa>fA;&3WyOXW#*KW*wj1{Wn0Hy&OD(r9Q#>ct{n8sp}ua3{gB}NSP2?#&J)rLiQEq%~FQ~X2528R8r_HVz^V($gF64#dN-?oTAN;iRAKVaq7iv{k zfs}W?jv@CivzPSWX74+j-yCr(N)A4>DfRa=gp@rbOHYIbN|!sSAE;~+heMt;nDzR9 zJz4%=KX&_vESLQz3SlOF`f2@klpH045IIdnijd;)cGERVI)zi8 zCQ^NSlo*0!Z&Gri);IRxbMZJOQDNUufWi zi?k8506=+qD*>jW!$S4uJOcv8Y4|fx zqSI$cK1YRqq7C`W`6H!XnW97^Ku~;Zf0u8TrZXgHa_me2zF82r9;0V`^7&0mkq_$S zMJrc4n3&S~qy{m3y0cy*P*&Y~J?%#|JOn9(K6Ck!FA?wBeYN>PzY@W3df`RK!;|+? z2#>Oq06Eg3c*}nRVH(J|&SV4cHAWv>e znUUq1ivkM{{$gE%=I>yNLh48uV`^0jt&J6L{=HZ~Or;ItA@asJ+N>cBQBUxYn*Qq+ zy2ZNCxH-*G6{Gc?*oYItPe?Ww?+H4=>`AHqSKB%t-hGZPf$&tg1k+ zKCn>O2`U&ez`i9o$+(y`1(m0gOrlc7`j&=`+pZ6>9;RizACmlfP%zF8dIF3$)o*k; zOvWsV`}&U%MCABo&`dij84LbljHs0sA~}Hms%`z~JHk1r(XTW9-#&DN00E?1dY&W& zJ7_U16sQM^DLfRx=g|W$`0_OPYUXIfcnJlT!JB5bH~hm9!uHmB$>I?`iKO3LsuHbJ zO!_lx7!x`yRIL*vIIRyTUdSCZN)zGBmgG#(>G0{UOnZ=Rg180oO#M%8FWAo@;So%H z{`Ijvp>*@|K(JAf)(ur5lDVSgwJK0IN@ZKRlGJ}1z$zGiGpw(%L>Z2ArU--rZlC(~ z8=qeu|96Kd!jG0!_!y^iWSgsfMl7_(3`0<`=<2-; z0k~KbMo1_VCQvn_;;Uyu;>9gztRmud7H zoqWiVW}!nFXYX@3R#Q1^LCHJHpYy#&kFbV7z?I}Urz`Wx_%wi`{$jK z_wuKELEo-I6=Y=xnL_5p*kXbh>@)Y8t({-22r@-Nj|bm#u96hBUgt`gG~fU6A`n1L zR&loKkJ}-M>^=wf{miJ7BHrrRTunE4{VH!#aX*TYDnl}cC(4o_5wkkxV~w(n|Btn| zfQqVn`@d&~89Ih;q`RdB9fqO1LqNJgT2REHyHOg4?nXdLx{+=~IweF93-5Qh^%u|c z^Zz{m_g(K=v({nG*?V&i?7h$4*Y&x+7rti!2!9{jlZ+z>5Qlv2%TI1eRuqI6rlevr zWO3iKy_U^DmTx*?iSd@*htVWYBU$xGN(WQ6((s+*j7#^2;K}>?UP)T=?s@_=w~`|Z z3fI{asD^qJ;fyuJq!XbFZ2M*<;Y?pIzBy+wpIU&m-PLiRJU&3!|n zq8EqZwBvg}mU6-Rjnyrl;xF_3sjyg45ihL|2&IO$!>P7@XvCPf!(aJ5dW+CyWGgsl zEb3n}6Ho$kR2MK`n!^->Q#?0(3y>(llj=7`Co~r~UhNBF zj;j@DCbT{7(en06hrYh#4^Gm0eMnr?7$o7pJ7uEe&trkK@8LP%ulp_{shquvhq{fO zY`R8roLk(Z5~~7O34I3*VAOLPaNmjca2ZlU2-7U?!3kn;iN$@ z{11rx!mIe+uyTbz|IX%1AXwx3V6T%i0VKa!O!5uCyt%j*n~?8aYrWX?01QAQ; zxXm#}%<0M`k-A}{Ei!@Cb&pUwSb zYcK|-P=@N^8%?++lj=Lbc5kJ{eLX$ei2`+}y+1c)6MvtY;&^g-=Wa2D?~9NE+r0TJ zS43s!RiWAt<=|VNePz5Kj|gXFa-;ENnxBa%evva5u+q3{SR~~&W>l@^tiR6R$eN(N z`>_l6a{G8( zH82*lTf07%t~fy%1Lf{4`j#d;a@0l%VEnEDNV9JYpI#dHpnHEXS^qPGq4soX+-s=9 z9m}?MHhrX9W(aco7}xUa&qK87sw`FPG7N+=FTtc!jprf(F0B0S2k8C2?pQwztwh{CY^Jxh zn$G2eTbpndgv6J)m_Ad@INl24@|%pM5qlaeC!*$r9x(2fM? zKc;596P4u@+O0I4u;^Y^hg~OxthVw>4DloOq^N680+<+6P*x7u@>akmp>gaLA)oU5 z=|ZAI={7t_y!1$+CP}rWFLsiJMrDu@nCL)$y0bM9$X30>;PTsWSKMZ*@b z>Mw#0ce$KF-qR8;^*}ADYvh9!u|(Xr$|skk`O+o2LJgUj!44kIS}f0ZXKN!wTAj;a z{S7Mh){1R|%`-B8ti$BR3v6 zW#IJw^vT{%5&arm7%{S68cLdHk7}GO=wucx9S9x#95z*_s=+TcX_f^h2>!yfIoo*K z&di2MIpUt8*>l1?aTo)Ql-tje%wm$hVk;sTMhcsTqk{%Q0p+8fmqm7dRT!FICo|`c zovkArq{1<=cqQzBrDpckq+vq=fQ?XR7g3vqzG;3%7|;5JW{0I(D419DWRY8hhA2+2 zGr6E7S#3>cmZgv7)R2T=5T{*d%cBQuhi#?bmnYcv)Cb>X_T=Gd`^#!;a=?^F3Z^&;Rsu(Hzyda$?rzjh9R%7#8{BM}Qu!ih|1A zGUoaR*$3tL;ak1UR*`M83Y&q<{%o^Cg}}&6D^ZnreyJDKd3GgoXSyE^Ed?-*BD6UZ z>fifo#9=|GeAKjDU}q+d$CKr_QV2FqD+M@Mf_+3ce2FHuI~A8F`nir-=}DIbe>H)K zkvp=C{4m{YNTOf~v+c<(Mz)wChZ&j$T$~sYc) z4*)EF&hF`5f?ec{rtwxMuGmjU;J9Opu=F@2g(bOAsK#KNMtE@>R*j`b-M+Yd(IZ>f zSd`+4Af|yWSva|g)VoS#6XjyEeVGLg^>D6(FSk2Lw}8%bBy>)KX-e>iecms? zPU}kph2j+t6mt1FT)<|sf@#8cSX&@lsszyvjam?yMDpz@dRBCr}3xAwXWhm>r z+lNjbl`NvdKe%0#;O-m^Z(^}@G(0C)EC zBOs>AAbsTS=j+n&!wd%e9hU4NiBl@;LyTixz8tFCHg7f!*@9EI%BQ4p9ddbQH8SZlKYup>I zX-@fa00?#qX=exC3N9fb}GzQxm;iMJf+&Ts}kUh0RWm1OI*SyBJjQSNJ%9L808D1X52^GFxxiydW6kerg zr4jZPAJY6Nv%vE#h)gWiFD}DWSa5=AmuTiQzTN35yweRALRyQ%xgR|ptN$vwoRn3H z2M)@z@LpU*=3Ph}u0LMtd?_D{i@e2#ei@=ss1CMk>I&PLRY5FK9nNXy$Swach$i=s z&OZp<-}7zVRjw5&;urj8^X<7#xxRj&`5%fgj_u_1m(>sMv;6Wk^7R*0zf$k_e)DLa z-6}TmHAHC1usi@;a^-WtT@1fy4742A76eMG@%+uRY2IHeV^k{1Q{2v2Wqux9jnL29 zw>^o0~Ayjg&q=yTJAW{Ta6>(2G;>vA;En|Z9!W4{J&-C#TbMBOPdK@sZ z(2@b0Gv~ZwmX-i|nc`~Ceve+eh`<4^9(o085!A`p$Et}9B}tt=;@i(JNq&w&zNd&E z_kF(m-4T@4#s~*_lO+Lon7aB%GQvI!SBK}hneT|!J@lXMU*@1Cj3dxB!ZGB^PA89b zJ?EP3z`$j$Woo_0rjM#2s{NqMj4HXs$`#rOCdr8ptUCfXU52RO5@My@l8?Z}EPVg| z_hLj9q0dncaS&L!!CcW~<2TqpNTWQGSHXqe!#cEg&HiO{ct5qh{PW7WLQ^rt`MX*5 zPN4C>uB|c~)FP@goUjx}qb<={g2m#?2=f~N>ZVGAM0fCuG9PE_vBXNe1CY6i1S`L~ z4E-CkCHe8vt2PusP_3$z|7Bz+wmIOb^#3KbO0ybfqpG3C|sgb$GZ3n1`^A`^`yjEuHUNqOWC{A@7v2@ZW; zjNO&gf?0`de%FuWXu$%w+SR{R5MPA%Sg%SuRc=*>*Sh>N3+<88KAzeBTB=wc zdwf!{%ehz;_Q`WeO^_S={8L2o0X`7$o7O}>`=jh2`pimb`PoyMKTZdKI4OYnuq8~H z3lkE3_x*oCJw3)50L0qyW4yKl!!f1N=W6clmNxyf^8W1p4DRS_TCngqUf!>7eos-6 zQU#lYiuwef-@bUn<-RSssEn~Qt1VCV?;o8tr8KX1?D9OqbOD{5`O*L7gF1}R=7)+f zOn$fq{31g`RnaiiBpM~3yeB0c$1Zp~KZ9)?;|+5JzTw@u+JiU>&S(J&b}K`@Rul z5~9v1c8I*xjvTZRO*M194)l0=<1r>^#I2NMkXd?`d(HS8E?~aT+7ZCXM25!kjBfC4 zbdG{ILVSmx7oLT8=dp5Q84%Xl4ZR{LDO~y#SAbK0Zh$vQa#~c!`!kO9m1MTY(?0Hi3=|sd* z;g-;!pyVmoagU5VFmE>UE96GE#-t#DJR#+JgUG_$BOdw&wBnRbcaI_vM#+R~W0dY$ZcKy6SoJYCSOsvU`<0t{ zJ#vC;0mrqU6p5d@R_m}RqZQtm_kiRiL;xw)UZbm5s;c01MEXAyd9v=+cUKvvx07m= zClHG?S;ffVLv`+A%C69n$b}GuQ9USlEdWWiy$ri9rgqeBx;2`bAt-H@@WNq* zqHfDl?s3(5<}jO5p>~XISG97?V9zMc?eC~cBZW? z3Sq1YD!Q5XKNNov=|Jymh0-1wLA;gp8|rth?NN(Y9MLH?!gep!TF4z%5C*(0NQV^| zPe0Wj0O-9OYw6*9F{4Zwj&FSiU4B)*93A2uY3beAn_xrf+5|La6ruZQvP<#ydJ(s1 zy00>tXp7IxN1v6{b1}72^$&`-PTV~`o;k?XvXi13z9 zzA(ik_Ta~0TwXG(K5w;$=}qdn=PWUfY(ZQ*xAcVsh^}<*AMh$wIl{Tu+Z8x^9%zm zBCHS=^HR#{?u9Nr;KS07q^fqDje;{DDeqT{Eqn9c3GNC%`Y?!2gw*mv$AFlaGhel` z^pwtO;I=D}s)yg5Sex+-BVUcxAGq`#$WF{oZJ+6iWuA(ls$ww*`D-=Fl~GIiCzzjW zeZ#zCfj>ktXDv8H|AMbF$|hUe`kpRAxaOgwQ{;Cm*&QI~Cib?l_a}yq?Ys+oJbvjU zgoa|L`DM)1Bwd3Mub8AZs%HjN;l^Z~<5-`s5X`v*N%u)T<25$5sD-M1fEF?RNWLbS1#l<1XvyVn&Oi|mUXo6l;X^-qst}{*yB-IAF&Cz%AL8I zRA)Ik4sf%{09}~QtqdlcrF8D1g{o?#V2*LY4^`W%3hMM3Y(CbM@;j`it=;PKU@!8V zFVPjg+WPo*xbK%q>ETADn4EXWzJwfxnax(|XRxwPxQ7tg@#zIJi*66Fm98 zS*t%K86pf*8r5OwtJCKSu;8B?l=8-f2IlFHbN28#5QtEMp+G3Uer;=%6$*hN5y7XQ zq_hth1Ib|k$r?G!sq6t=R^z3@76b?-YShX?sk-a^HSfA-8*cPft66&c`CjAUyCYc= zWd1p$3R&xuxChibWI2m@&tA!59=|JBYGc-bGYW?}cj0tt^&MZ*^_KD3mZElk9PsKf zLTAF_)j!%9IS{-e<$3z;-%Jt#&?;{7tJi9GB>G$0t~nx*=vOel1{nr9qQi6(NM_-Q z@@T2eRiKlb=+F zaG5RaTs_nQ!f6w@WwW)8Bc3Jjd!m>h+6Ui$Od<`{8MTQix3~bFq%;4>Z&krXTE&nt zmpe7NUpq@f*1H17Ihv^JiCj0RJ8&4Vxoqp@kMGP2@Q3a*+t6t>a>7rCt2Q!;^d*W^ za@e1T<8!9!0D#&SPCN_th}$2<;=CzpTem^R^t!9aEPN1%*|GkPV2N=sP9*mWC1Y=X zhIE0;JW!?yPeJrm`wzp~LgS0l-_bybgp6omv|I*x>C2ZgB8Q&>0tBnCf!!uzS?(ma zt{JB!r?$3)zY)#f@t}PYACz>h;!q%cdq|zxHB|;Q@_0m8P=+Z=jr!q9CJb+%bCAek zsz0ioO)wIxfxG6XvgYtea&w-z>$>*JoU9vJasStRY2tzk)+vNnx>7qus*5`|;kw!p42pI7MV-OyBYV?ULs<&+fw(r$f@)*;$Mr1!Av&cvk^gEaI)$u+^Ma-@=#9P)YE8S?YF+fZn?oND(9Y4F;^HSd}h> zm3V?Qg9NcSViih8&0nEljoa#fkMJ#G^t zDGr;TcpkG%P)mF#l{LMG*JIF_YST>z6)GN@ko;B;_q2Xu*5eEh=367Q*lVy%s-_JGR)Cpp2ajswYP3RM}n)+cYZ0 zsB<8@004}Td+7-SBGHOs%^y^-pSW>roq5xeTi<`rB3zIH5BoOp=I5yVLniZkC98PK z!djwTd9wNgN><_BSeW_IiQu>h-GOwc2)`-DuV~Keo8B)jwTBI@jM9FijKa|KW*l?+ zL!za23Aq*$?_Fg|#|XFUVnYQXNJbn$7uKJO7(QMQdfym4>|Pw?x^@PQ6!E;QKGi#l zVu&|@oae)JiKFJl)O*2qlk}I2@qM}mDfTz)t`SBV+JsHM-Pwv%B|`e$TG$Uu7CFz5 zlZd{$nck&m&V5}F2IOb8EY{+3LLKJA9&@&b4zgg{IZTzHCaEw}LjZ?ueBE@r2`?k= z0*LG#p}@c}#-w(tBjVEn(gwu{sNi0r3tZPogaB1i2iIv7S)nCzcT}FKuutn7y10Cj zLvXz_pu+=aS7TzZ)%ns=JBx~35QeP%5Tv?G1#tS9{J7wN?r+sh2ZIf0rMK5*GyOf~ z0*s!E%=g2Yscp=&N=HpRp+)u>s75fu7HAD05hOj7ER19p$LKP@;Ns5S9Gt5)^P+r9 zTCWB?b4!D(>m{N&teED&wwz&Y?g;MlHi5v~C{;yx6<}+sO@e%}` zo`Y~gec-qO{emw{e#BIQGQsf%Mum3+BIJuneT=!V?0}`c;hs%hP-t{^PhtP_+I)h- z!5otBQAx6@326#SrorhyL%xgNp{xm{V#|?L0Tw4dicG5R!3K_^J1_U>!Fum#P@X#| zq?!)9Qk|E55T`fAWb?ZZvEC$U;GDzhEBJi3gebe55r3^aJQh@q9rBD#kD42-{du|n zD)ldbV^nM0wZ`9u!1btg%lx95EKWt?VWtIdutwK}3iC`f-4;eXzbuCM+VNDd<+mpV z*C|fk%;;2#^&4EBt5vUW!H@`AFeaL+)5 z6}%!73qSdPDjAvcO{ooutmUE)IftjK!eqG?_ijM%veZ8tsJyG#CfyhXIdmP>E;YaB zmi-0rn!9)Mxa4}ANiTOFGx)mU*VhTXzW^zqIofMayvCJdMv&A47FgiH_ND&NmMEQ?eE zC|lZkDgm|hDE)19uD(4HCs0Ce{-ilhKF+$n%Oj#-wc3H#=pN@wp{lBAu`Hq@%Od_zZZk7D+sN*jh@;g3plY{J%&&W62zX#tN zj-4N4rdkv>f+COSS8#~v%muE(n5PYW@hUQKH12(@T&zQwnqnv&c)3I;N>O}fQs3rz z$h8nhrN}HBB_?k_Ax(ct+ijF2DL@8B9*Sp?7eP z09tBs>?Q%&QmMtVagf#Nu{Z=6JERe$n^3lpSE^Iy+J$vc1`#2PXZi7T#Mz~J+{?=B z(!X#-H$t!8+F`X3JI2#?--Y*9SkJ52w{fJJB!2zm2W-K14=`Bqo?uV5m8$it8?IuC zrnhNT5yko-s}SKT5kYQLqC0@ls{SYOZJ;Uw(EKlZ6eiDayx^VcsluH$NP8&kiy_O zl5nioAIF;$tmp+}PRMF^OmNkS(>8QnfHcfIsko(O7{$FS|y3IMHt|ZHQ!5AQ>6CTXv%qE+BAZ)B19tvV51hN#i4&AAIB~B?AO6-+2covN{nQw^#7zdC{D9TyXo_pN6k5TLU zaY4P$fztpURQ4c3zvtAdf}Q3q>2{dlkG}vOlCu|*xKL2!sfK7hMBz-Ycce4$!5>0y zb?5T?pezJiJTQV1qyhciKb2YUfnCx%+{fa$yWOOVj~guAzOmgZ2Y}uE1^GQlxlFiC zcH<^TN8DpRcx+lr%Q|#m_U)UuQys_rk19QebQTb+$=)o#Rzv_n~rfDezA-!4Z9_FU;xEBlQ&?ON_*` zu35uI=@!9WU+6G`6noZcyV0^ z6^;7z1mTcBQP7E*wFh8!W>5!VIlsE%bKbmFC)g7Pi#cQYMTLHD)sWM;4mxJBITYoa zi_gR-J9@adKO%D+5EIsEiR-Xo`vGz3tDf#+(2r>$A!}vZV?K% z729I5vEp){j_dTA&{Po<1M;1B|HQCD$4a$NY1>(qCKr_@Nq46Ivy2>Bh^xPHa3TcR zd_i;LqBPvTmWsA0qZsZ@fCHd_ot&552k?(7>W1&vXC}xwjVWd=Z`ao*`|5J~;SL%Z{_lPv@yoLjp$IT`0w*;?Or$pwuz%}MzN3;} zCh;Q%@*9N?nP*2@M+G7H7*>a@#d;J)1(G?dEl;KohlYL=wnl`Ug0_r&z%H44!&)7nvcl=-C$ zlNnjZ)3Ez>O$|m)qUBih?^tr-QDeU0SE1fUm1OpR*v8&)9Nj{@Af|CZ-Cul)^PbAb zSGJly^Wlp&o^=o*7THY0ezYKo^n09;gY^xD@+WN){Txi`4S8D9G-WfLWancXwY;(+P{GJ^c&^$$$6UW|!x>Wo7TlhS0VD1KS#j9YnIKPsJ zhPU4pi9PLDC%z5G7re7nctK{6HMhCrU_&NE!OW_$Be7QBbSdk0 zK+Au6GimR`M(9%%^P?g7aVT5DsD?>>#+uRprpa?7+f(-8Zh20W3YeU-?H`k)51M4{ zmp(Ko$IWZ1^ZjZ~c`IL*enIh@JL$DX-9x);Pz-Lz`iC{UaJzQ4d*jsvf|VE$GBUvA zu5g--8Ns|0bC+LsG))-8@(F!W@d^e`Bji07IDj{GGh;KmzzK_8sMABpF0F5JX9Q`S z(1lqTnF{Wa-I%eq0!2)2RfH7MFMG_&4&?)xH>GMvO&aWjB?UFugy~U zGA`&kT?9pOn0~tbHRH$F>6Utjj;ZM5C-e%vemXd>rN2(xzL)WGY+_(#e^{Gdb!)%@ zd#Z7&oZaX3uKi7wFBo6_y4~jvWU|v8M4u!Gdm>F>8usKT@zKJYn_FVHv z-{DWYKtuM7B%Lo$D9zKvBK#NKexI#`G0I9I*nJ8zV6lkx-_LV|tpOqkThdH&5*mq> zy*pH_fvZ9;aPE9@@rOQ1^M}bTl$B4JK(NBk-Fd50qP!gAlaGijfv(rVmpZF{wCLXDbdhpUal!7+gm87@rzmzg+p+sAc+v~5Q zJN!GB)=durtW(4j$+2Scpq|&nH*#XO#hu#l!LJJ|_ z)(kazGVS_yyC~MYqjncCCPioZEFdPLa5VM%#N`xzR_Ugz;t-o$r?5q%Bw^Q_+v=>s zW?JlNVIb5z(t1J1x)p|t!O?UlOR!jkQ0*ZRli=Ls*U6ALygQs)ePpFw)hzfxgrrCe zcqZgCX_{v;i86*Y@^LN=-n?6S#>M_GyW~_i?;)-hfk;R@BF+~IBfNig?e;6bM}_{f zMh_u#SD`Nv8dN~XU1A@jIe?mvv)!r>eUcGeWA3E$wzln}NI7_}fer4*JdJ2#(_Q?r zNyb)*CtI)fZBl{Jg#bgmC;P*?g1F&HUlgyj297jQOq}uB+i&b}_&~h&w>aRUG*fb4 z+(YYOob-==Is7lW&?see$oF8*5K1uv!Vg{TjUr@ua>$EvJSxiOlzED#I@&5fcs?M% zbVVf3CL2Rv%BE=yqKE<0RHin?wd#P7i}VyixW_yA)sVLEdqs!p`byKW*zt2;{Fyzg zdYw=mcI)?1+^M>ht$7xCued8-dB(IDvBfu%>5$Uh&I6`jO&Q3Z{nNLKsGe_5?TXY! zZA%Zv&yU$4D7bYVs3a?BSAvkMKic4jJCz7t!wAe=w%RF6VxhLHeI^T%gW)mdXuKB8 z%UvE76OlK|KMe{;6(O?M-DI*cSv>fzd_Yg@EV=@<5<}yr#zUM})>#?f2pn_7+*@Fb zYnqhGdvdbDN$$a;(6;b?p#Z7HS5e#!VaUc)ul=l-iG+ckYw@5;HNH7=Q5vuN!65GGudNf4*fD$NcazeRR&gRlw(dYI zfGd`}@zez7zHc}Z?0@HF*ZYSnjS17BE9E%U97QDorwZ>!G;$Lw1#JNJ%0+rRZR*RO zT+5_Q12`ots{{3$wnCh9_>BmXZA7ZCx8?Q^kgY;#iQ~Ex+lb;y#{KmVYK5E2`LLi5 z+ttG7BaHf!;qx98Ti&9V$`zP(c3={#!k>L6=tNY&dbRN9@7uF6awMm15zhV+SW;ev zBa!nT!$4goT_EyVIjSSsF%q!}`Mlr=-?g|TN&JQ<&b3Dk0l*4?+U+Ja^!8HOIpVv? zWl)AFT@1d0cfjOMsH;_7v0{b=-6?MszVWQ$&<7hvmlobS2})Eir9n={GtE`g3}jq3 z^Qr-DEZ>Oi63#{AjV@7OIvN>c9w&Ybi)gJ0n8Q?wM&x9Y80$LmS*3N1K zPdfZ6<-(Y+xAYDS+GL$hiK(3qHHHnrb%05SOeL`aE-jvUNgQm?nP95LLpUDUb^%sc z&;w8&Gm~PIPNnzyy*vH;zyr=9$75FM+fdkg49qscGdpZuZpLF+`r;XnkJA>BN7}x! zxhl9$8%}3R!_rhZGK}xBvD;*YI+KgR--|HNs}3#%t+W#SV6MxPbM4B-0>TIYK*2h& zyo$M)1=0=seOobj?UF7_P5it&41XC+wflV3DA70{972XSVkib6s0UEU(Zx4L%M;rp zGPh`F05cX@V4zel-;2(i+;uXHr^!z%(gAe&$W$U*1ZjrLxC!!u+m( z-ia5I69X2!a$ff4pCy*lqBX8877!z(Qi|1h!=Z17--mgkGm&S5fx{h=q8=6xN@mm^ z3UdUKCVhTfE|yc>y1SC2F;NzlQ-s=Ia`5R`(dH3o_!3|G{kA}gdXH4PNVNP66%A=0pu1VX^P{w>T zW&D|QSbqyx?>o;zw0{1uc3gH8w>SMF*5J&x5Px&FSUyr}D5K{b{*}&RgGak}emD8B z%ej$#^;SVw&?FNRrMOn~@zn?|KeES1#J$$@P-NWi*x8yxnoWN#L+Q#M_FBw6vH4?t zXPXD=y&*q#i5!aNmjn2l#f_fw(*w8iip>f;ad5tV7DU^9x5?W2SVnvBVs651xB0*|Dp30gU*4OgeG)q50La#Np)>AK%hrghozcG6J9t zz6fQ{P5zOnK|D2_bCX^XhkPgy3)5V@+*}8(!X&uyPTm|5TP=q*tAsvm!5N? z#jJYRJq*))hNsUp<`|Y|%J&31_~!Hj^j(I(aTkxm8*F-79wcB&gbk|Clbdhelcs{< z3|htxFHEDTNngHcIR8HVPT#QKV8UMD&9f_}&$XU(|FVp&Q#PtPP%CFg+^(Xp-kK0V z4N?!9A*M}=+WaEnAh+=W4XX8q)s#PZmIq|mB}};b2tDrq>Zt! zU7kBlW4*nww(U@*@?et-I~0s>L(1SD9S0zjY8ggrbcHZ-d|z3&u_<)di*(bufbqyC z26xkXb#3>+crWtpjWW~m{6^bfFDE{w%EgY5v_NOa?LeMWEQuZOshF>`_*LOu5IiNL zAe$EZaH|0V*@)o0W!ugV-i~JhZfcPR)cXT6)z?e6bx5O-f}MFtp8?j~{HyK5zvW1O z??C>EUD5rA*&xOCYMwb>;0s&94_I#cj4GalU{XxcDoc#}Cw$HhEM)3zXY%)wH^ROa z&)7%IzV{Pz6Y2(~48e$W^GoHO=$`{NYSpykY4n2Op%MB7$f8egUc|oJ$Ie%}8YD~) z>f?%N3|zfd_6#bf4iF1o$XoJNe|andoA-mZ7ed*#7}{gSv0_$; zof7su9!1at)t!TTCPxLvIR*pM?fC9#&oQfZY}-q4Ki@KN84)r8wP!iuEbt1>rkm{_ zsyjm-Fa7|pO`~_X0j5df?K7vWBdtlJlXc!3wGTL7&tUHo`*fSDaN730!cmAXz3dl> zYs31`E$e4bw-Eb+?kkh7+ zOesMsu6Z`WjKKNNiJN#5krdcABr(p^h_#Ke9g z!6Yd2!CU0AIWQOf3Z6|? z3j=9`jZPhcTWMJDC8n*q543$~BSm?YFdIM?jK`Hg$BXJQPXPL~&iDkXuW=2y7#oW) zy@leqmncFP4Qgt!a}sEB2-JOvj8^+-zL~N#Zc8sb3k9xj<}iuoeErlWqp4n1&;_H{ zmcLI6-6W1V^I8^O!9 zQz20g?`67ijT$XK-DGUce5XB_&#e^m5m)6)eDr#Qq33rhTM4(f5B|8z0{*zGHq7aXbjdqdsAflrzn(Ctr-9y9T*o|in6P1F^dIF7bFrk!$O&JQ!fl_>{vE{mXoUzZGlLG0@V+T@mjZYkB% zQ4h8U38%P~vW|aANgN3BVuz$Hj+r$6=jpg|u2@fi zb0asA-@R!F#!yaOO(V1o#d9pvbkB&6jU}plFeWyJT2>gJmFS@F?U!4pg%6(Q|foRrcA`VnDzP}Yy3x>c4GYY>12^W8*;4G z--CWUufa*L>k@E%<}dVQCq=c$!T*KdU;(XH6A|A0x31q?sCT}L9!OBBKK|a*!9wz5S{8b8?SU-=>TCp#c~qZ`r?1KGJs`QMBud)z;2vTxmBy=eH2 zoEbaKlLu<=LR1F7l_YofF91LEKhp_uzhDO#U0xEJKrZf0MVZBT&mjMloCsP;>$0z^ zsI6@LTYuq={-Zb6Q&TKw7n;2H;*RlV@c3Kc?qxe=78z z8UlPAV0Y__x7v#1h(_m!M&%p@cLJ``w!MQ-=%hVjE=vvn+u@;##Ncd6qJUlA1={Xy zZ$$vHE7gMuYIofO0XgXtrn-XuQ-t+D{{;WDcx(0BS8Ak2dG0iWv$>$zr6)hu|4%L4 z*1%uEc3>mPj!j0ITVBqghnbX+oUwiZ1~bd2b_w^5-Uvdv|9)8SvQHhn*0I#peTTjd zD4MGx&`AftM9**3IxmGooka5^&NgstkXllwXqhn;NHE$G{PS-m-=EUTu;VJNSbAN@ zaIq8tf4SV)v$OqCGcIUlTj1ATD-!f({nL!J^j(HqMA&|d2~F3NTQ#*ob5a-<4Vo*z z&J!NGZuWAIHr7Z!th!iy8q{3u=NEvkK^o07zf+V)@&sV7bWRJ&boa_q#mwjIae`Sa#x}1?Tz`xgox_rHzfVvoC%Yp3AS|ah)EG_cPBv z0YBLLeK(+~TAq5e7O(}JzjAt!?~C`uP20V_lP6H*l)Asq_(FB6oGgX;?ytLnmgHNo zso-%C)lwIJ_-t`MB|hU<^ETod!EEZf6Q+!(yd>B~FGj=qL`WI)He8Penm=G=52f*B z2t}?~cq1#1C6ysfZ5a=HfQyI#!^MpfNkxbS;v)?p5dEI zbO2Y`k2J!r?>=C*g<;!?sbF;HQfT6Fgr$UaC`GdceLchSKLaoJ6UCc0(JlQ#z zC*Q|LN?H?{0+FqSE1|U>_19 z&F@tegVCrKKDW~TX~Q-*o8KAw>4WO6_;Mp+$dT`7dN2QjFc3hm^dY-Qdr^{@PGUga*kwMZ$ zvu;vRcdsUjo4h(s1(vG+Z0Jd3e(j1WOwUN;U3uPZ>Cq6h?F3u;5aW}^Cr+b`iH-K$ zvUpMIRrICCvGu*UvMpQ+hUJ@AlU)RJ0cI2T{cMtz z%1UgKDKgLK8bj*@e-X<>_-cpVe0G8#ql+)=O7U7fm2%1CiqfRtj%ul=U9<||RtV$z z;u}(lIrtn?s@D>AD66HBN9e1@sc>FdgC+UD0PCF2)4#^`1~G@ri9dk&%0)PT^>p@Q z@MCY88SK>mnb17N<|C*{?Ijcf5x>~P}3A*RW@L91E7 zGjp-I{lGq`;47FQ(j?FHzAhCPuQFX(2kb}w0hm;f47|00?+k_sA>%4yNLLeLAiQ>MBuQ~-v5$f;J>8}a3E&_ z>y3bVy$C(kx)k8pQHB36Qx*tHt3QRdg+2#jK3l`=5ZL<*@X_fK={$W>%C_zjd@xWl zKH@pj0V*YzJK0>5@!Li8lIh7(j?dmlGd%s)<}avp0NLeRwGi)7D`qAhgZ)SPK5zGT zEQH&KQ>;zCzPi);sFc=BVr-?QO5g3?6{5|7T*Z^_NrDLqz#Wgob00Kau9J_9Oc?!d z-rXBtZ$l&1YCba2yCsU)ccLp%BKOt#<{uovkN*Nl#T##|X?`DhFmXi!02426Cd+pQ zR6mEo77P#m;LLTDH!nNYUvdCH zIhkty{YO3^B*OkBT3e!{t6{D0hZS5$&VWjESzQmH&v+M5$~UVl3^YM5kclGRjz|bX zv;+~fU%64kTFeRUFr%d+jW(&~6r+H$HqI-kGb z(&XFQ(oum*sbYrUx?S`}7B*}MaYsMsL->lO}>X2$BZYpRT+uA3kJAv3Nk@ zwol58bjJBw((xkZsY3S#!E$5{+jNs4_WD>!%KKiEz`6d9<;J2)-@{p2mC zNp-!qJQE#JxA~@X8I+c`qc83^x#&SlOcrNSdYhes@gbddzh%@iHSVo6 z@;+pxUd-N)&pg<&triB+Wb@!?%{3%;H%{->$!8*xL z!4kZYdx}b&f>i}PV_4$1?Ke$`m0}gNOwl>Af0BK`_^>(np1bPy60^3_7N-TuW&(GLl{WKX1dy$e1oVF?+#3lTEmuq4fPsSN=EA1qA6(EgN7m;v`8 zW3}VMZ9u=&ckTz=*<|TyTHIsl<^_rgogQ3F4ab}c+{?mfLZ_K$6w}8Rho18~8Ti?a zaka3=S)qFkFi$KnFzqnp!L7FiHOVJUd@-jI6+io>gWtuJQF4eIrEGb(p-`PIxh@Rofi`jFF5M zV+0ZX1;9#NC_=L)H}2HG0A$dGq8lDy2{IF>i5`+~zSM?ya8KMD2?gvtu@1J&HO8HG zEX_E$_eqB1r+wjHfU%30UvpFb0^FW{w)3G2Zhsn+C z*!2mZXw}0ax2H8mU;jZG;y(*D{RO~ocEHuLzupn}TSqb9TTM1!xicz6M|eL{_~&1M zo8FF|^#A61ED%%Mep^eVU-q`TyNT&!8+0Y!xl+F%L`^NMewvWdA+7@7Ns5_S8c3zy zuMn-G|DNl=cmLz5EU}!9^Br=Iu|+9x-c3o?jTR?Af~cb0w=|M2o-(;joqM_d5W907 z2X&S*{B2_AGN!=w2VN7>(^Ev6nWdAy$@c%xV(wjvpM62ev3>K&-z@L<-{!3>sMbgb zvFI;+KF?o;H8d|uSB(5%>Y&V}FCCbS65GCpD@RJ162U4~DYb~00=S=+n)zyXcS z+63>{O!1D@`Uz_ST-=jtr3ua2TAZ8Y*JY#-C}{sfN~K8rR|=QoDvth(JFxe`5FImK Vw&xjp-lw?*^$cTp7vLcbBkiE)CC0SWzWRuV^N@*Y?d&`bcDT<8DY*J=M z+53B(b$8!)_xtnb@6Vry`(1CjuIoHsuje?9<9WQ!o63sEsVEpJNF)-K>?WLW&@y9x=6Q{3`NYrnL|5gO?P&1K8Y$RFfBkET}zqLE4Yc#blf3G$S zQ(vt@r_63lNx^+BQ)SbOCa#vL_h+LN&bNGde|GYwLTj8-NVJfNS%{G5*5CvMGgASD z##=W9H?I`oytV2EhvJrFDk^J^-#?O9EV1BFzAm2ao#EBu#>-zrGpC#ToKl^#SF%p! zh%i(8;FA9Sa@RcnDg9i_3x~|i3R39B{+h^^ER%bg6;`6_yM_P$E&L^GC&TTx%{xen z$G^#6zGAoH-~aZql5N3r>c&`~Tb@Y4zyAS$XS_9r+x^#9L<9Q*u{i&H8QYQ<|M7k# z?QO3u|M_?P&0W*y|9_ibEAs!%+9*V4WT<}q`c>H0^2iYnZyHwq+i#zy70o5y>BmE=A_+l3jSwO8Ku(26 zdm|Gn%=Wv@l(2HjrWH;FSA|QAele{H`|o?aoF6T=WZt8fpQU2Z?lRr(mmKSmmq#mc zZG7+izdy`fCNVj=zIb`jvS(qB+pK(4>G;%?#U)wEkiOn;EC2Y-#*v}4;>LlxxE-?F z#O&(xtb0xlQ~MlsaByfTb}LRyN}^|BNgW%ra=3a`VCFRO<3gug-09P(D0)UlZKLAB zLDQh1p!XFONmcYMNR{&P@-N-p>{?n)qGfqkzdzl7;DGH&+rhVQ-ozVKhf$^G9?lNB zf8V$@$2{Mv``Soe5B20gU0Ho`M1-W6-M2drA3pS^+`3&~zjMgn4X+#SEY|Om)o^p6c!pjJ9Yoz!?-76_K5~%{2S~6T>g-{9B5i zt3STHk5z7csPCH4-*4>Y<5OXpZCV>GJJ^&Ken?zg&}r%tKB)Li^}DL7#wYe22_1z_ zX65&}f)6=lyng-q{{8#Wg-+9rgKm9K?8}>)wCL#QE{iZ{w~Q9eTg=YPysNBKh>3}b z%_%RJ6Q6FoGFTJoS?a$n$)qkeK`ZS{u((qW1qH?6{4?FUhL(ke1%WHQC&|{VF@1e~ zUGQO-{JE*&r0+dtN$Kgz^V6eEzFQA$VrJ$|YDj!$P*z@Dt)wJAdB41(Lc!ocP|!fT zeWymT>tcO^+OD@{WoCE_3TkT26DMvQp6id&4nKPAnAbH=&#yy6N%8T!D}x2)i3`s% zsS~jKcFMND=18^pbSO6u57T0mu_MEAy#s%g8so^+)UF2A^Lr2i-QC^z(0iONGu=M< zxKW$gABKxvYb9!YSY5BS&#$FojQ;lRlFQhuwZ#2#4s`plHWrK)nN7?NCZ*lKb0;D( zF;TQ^Y-*~}n~F)mxQ4AKI6OR@&J@>mr=XxFMcQC&Uiy;ziT(Y)z%PfyhC&3n#dF5W%P@=?dK&@eQBRpLyNR$9@> zBP@Bq13sOLA0nSV-A+bE)}G$+{@yOLx3}moU%9d*6T)Y{B)0Ltfst-dM$IwPJ2;pq zdvB*~;2DRn^lD?nIjt6T_Qmsh;!86L+^Km3tY1-Dk^fsdI%a- zF?0CZ4%F_b43}6A_J}t#pLGaA>{>5WyDimia?aFFah&*gJk7~XEpNKRY4Vdnz}7xN z&!4aFkMx=7@}yyG>TsPm|Jv8bMEnCHD!(txY2wXBCFA;dmD0(8!*eIX-Iiu;htf~+ z67OZ0t?g%)q?uB?metuxZPZJrY*t13-?MjhQvTcqV=3b}#V55%X+??aHty85Ur>@*R3}o7lWg^BW8~Q2$0#4pfo7v{jm{z$jWcIb zv(1`JCkGoCC0rL2isc;~o-^>CIvZNN@S`GF*fNZBK)86;FW+w1vCcqWK7d6$%eqI# z%gakPaBgzQ=#W}q?8(PZzg9e~K)wW`Bt+(Ry6Obp4-9;I@JjEaQk{$oH%E$>UF(d* z-IkmSf0XkCrY3)|$NuYOhTYqx#F+Go_+hYwTM_5LKwNm^hsOuL4h%GZ(vsPD?&}|o zHiFL7yYu3QN9?jKMJ@&YtP=bKa%YFNisv*^8k%r{iGAU2XV$G-*R;)Tpf;xTyOP_S z8pq5|S#hVSdgAXrFP1+qV^-YQGC01pQw1a$FhFL_B1Y)&iP(6 z9f!=LmQI&xJ>tbjeW(Tfao48IV$9SBnW+-2&q^`Q&zXuZ6>a$gf|d+h4XVo2cO&H zQ=*bon3z~DQe@RFRall{mi(Z%Rp;%Q+a=vK$)_`Y$58?ozwDAwk(R!WGH*Lr&!rH4 zcu_NG-LC&2s={@yaSHcduQ$cCyLLwMbBcRV2K^?@uT=lcSNOxivBa?U!oH z-j~L={r!df5A5G>^ZoPN5LZRql=Z@>+j4=XQ>7V#O2FS~dc>T$sm)s>e}l6avMS}- z=g*&gdnP6(v?HGjnl;uJjP%<4_#)err(f(E+ZDnozPvC#$=KIAs->rAP9f5`;N0bW zz4PBY?H;0hrJ@e_AS9>X_vTF%W8?T}o>!U2ZZkBrT%4E~sAD{MIXdv(y|npI6#rHc z*V(TRiFNKl5cSNBhc90WUG6_FvERR>q{PplpxuHQRnn{~^q}owv%&g=(sCmpfx6Fc zZ~NuEel6ARG+Nk{(r|iiV!(iz^|13PLqo&T*;s{;EW?Tij(%6rydG)3(Rp$8S&n5V zzbu++EgE4+{CNSg9C5OLUpHg?ix;~3&fmSP4;z$HsukS6eLKu`&ZII#SSc_I(Xu$C zzg!z}#1ox1`NfMvE?qoLWDI$ z1sqN+@u3O1c9VdHUr_w&W1{H(gZ!zo94Ac;T5H_hNq&riiJIZN!mdhf-MUpf=h9mQ15+!LkokRjK3oAt50|pEGDcV4N>pnj4BejNtvbP1-J1z(m-!(wryD3w;tp zlNQsRZp9Dw=%*qIWoxOlVhgqczjOgdoxpaacC&>*Dqh%Y+O32 z=M=&YozA>inLqH|$}D}D>)%^aBPp1B=m~miTbpUxk*{dHG4c-wE#2lrOmwP(i{{%$ zP3vM60;87}=b4&%K7T&BNOTZ{?QU-F#KtYw*46~k0`RuTw|I7H0?TXs>Ka-0hyxm` zZ%?XT0r%d$HR{uG;jW2B;Vzn}gI7P6&`4ZjJ}x6u-r8DFHJzAt#B@~AfG&bi9!WBD1^Iy0*e zC!uF%RTUeEJbY_iD7f+86wI9gP~u|MtwQicTPzNGZ6GHRR&yiv#ZD#j)U1b-7w4yk zetfMU8twM&+v`y%)<`(bPYsv9e}DJwd6knVeGzLXd5RihKs5^Nh67Q@hI2dlfrcH$ zN0B7uA3oGSztTsbDb!t|_%lZFsi}>3IgV%9kDjsp_DSX0vu8hk{7B5S{8d{xWl@v? zA+=mxi*n3cWBs>@ar5&l9zJ}y^7InbL8ql$&Og(=CQ(Fep~p&O)5eWa2th7RPH9|U zlKmq}K6$Z(sv? z6`qJrGH7~DT?_i7xYQ)3|InzgjvCfXi-}oi2Lbu;sXQAr0l@RhCb_nmnC3>!*QayF*(HW;m6#!PcvUy`t^=o0stDQU6<{)N@n)71`@yFUJ95O zI5W3lcq6Xq)akaVv4{`ip4*?bzQ;`L#8-X#e1} zlJ^ixjXX_6-d=@%&#e80;u4$hRL&McZ@iRMXIiK^dao zyt(srIVo!ge--~ftBt>zR~Jrq41L=`%Ci3Ru4=v{Ynt5)*viV9267`bn@7^#^{4t_ zd>O1TC@#+Eo-a{nh;lI0l-7h?>fkh3X}tKKJ%0}l*Iy+zdTB!B?%liE#jb^6P9p~q z%fd$tNi7ureQ%;K_)u?S6f7kww0Uce2?QYpb$a)lH)WZ0m57_Hd5{cw{Z;@MJkvjx_t_f22kp&$iI+`;k zI=UZicap`v)OV}n{BSP)rcE|H!grGmk_-!~ z#(TXBDQmnbw~5v_@5mzmb5qZXpbY{@80NN4etoE)7#;n_czkTE=FvU_-+0&BjC`Kd*500tHZHz6QFj?(XYU7)mAJfqg>mMedz)nd$%fcbx~r{#aS7u4 z_t%ma_%R79y1KejF%~1v8HFxA+P{DQ$)-_=5sQE<^kvK!gf$yeEwVJkIBgfqM^Nc^JeEZR>^tk zKX7=2pS1{cOSaj=XZfwzyciVVs6yOPu!!~3OF|(#6+`1$#2wpe9nTvWWSh4Nfy~J- zEiL6voF=u<{26rSlCrWlRn^q|8rngiEV2k5Ff-PTokriq3Y$01t)XWAlw7^4X6jEo zZtMl#POy*UksOn{of=wNOvAvzGN1VN?NeE?VufNd11Xs0k3e$Q{QTzT#?o>Neb?C- zIXO9BA$xm!>`4{*3jke7$fh?NR=!O6`uVq5Rg(cen~ zCcvfpHCg4OeMf=Sm*<*_8Eq`>>~f@z9wmOkva?90DZ}{V_S3u!e5cYQJ{tUN*){6i z+}s3iTKr}tQ3n)Qk0=(Os5z=#mv zhrR8#5((8?{j*w0I-&AMM?|ne&;i4F*Zj5q^0!a>AZS2?JE@tZ0Ue_$TK1mrRH>_( z2?QCr6DQ)Yya4$dgwXVHkL&mKR7^t2jl{k+n57l&lnvf{?izN2N#k~LadB0cIFD>T zbTo7iPXr=zr4Ha$08vn)+)jxV0_0~S5@^X1S{FV!-zZ4qjp-J zmbF1+I%=PVdwwojWkOb#x>;lLzLl2XYq3+09&JI^BliJ2<-)?k6caa*v>AR!RbFhc zPDl~KgCSiInF`TuD7SdgJgO}GfRTTg;~*Ch%wT}qLX>sk)2E-kr&G1F<-q$Ju~q{3 z7@4M@ZBFtE5#rDs>Fnl#DNgFIw+E4um6gqCzC?t%l$2EHDLzt`?(Y;+j>CqfoX#v2 z35T?{a@8u0)29<4N@}-W(?kq`6?AlTWSrt9dKZA+mywZFk5y{{IFcF)^V{GgW>gG;`;OHMeE+1s}H(M&52k5nhWCbKEM?eYagN!c{LrS`pPoI8_ zvV)G2sF;k%X@O)zJ185!jS{xnEG}La9OdHUYXD+XS6AnBb8~xJTAB!+PUWaY?B&apD{~VjF|o1b7P&kJ z51t04KhT06O+e%15e8OPxAruq6(p^HMhjUdAsp?`Ve<3!#XH`oW)@*X#-ZyG2wJ8S z+?S9rQOj=m`#0Jbjc+3;yFsb%$Fc5`ufxMB%d_FjDiDAMwn70ey^27}MP|RDLn@y=gW#L>MfXrizNnlj$%Cw=+l*4cxAvMVkniydGAU zf{LmkaEJWh3!|^)L5%w^+;E)wmH_r{h7xnj&rbuwmY{h{mNv2K^&A0*wo6Dz__2s< zAGr9T25L7z`0+}JGMo8z`CZi<4``3}M`ZEM8k2g`G5 z%eA}0owv(sr=RsW<$` z;N*N%TCh0Pn(el{G~^F-K7l5sdz*pp=j`A}LPA1dbQz1&Nw?Vw{ZyxAh(-6q!Ys7? zsyaLM0j7gE!Aaj60|13j4Y%62e}7$45_I=&q(yuF)+RZ5d0U9urbCS>O)o6FUwh3p zq`4Y~#>K@E(sGkaV}@ac&1m7YT>b_YW>9@J2iM9a#9~8}z8jyt{q&H3E3@_w=e3AS z_gJgXZ`J{zyhB{>*l}#fjvX=~ka_`B3>Ks`Y;0^iwRWu~J$m+=7n*YM@Z4*+5Uz?- z3O|z+&|q3PvIVUpe<-y;9r`2qr+y$&rty~b4x^u*8SIe7rG$+@bqDI%V*XR~DD&N_ zHq`OvjdV}m#W6y)i<0qEg&t1La>)3Fnv9Hh$JHJx@yU9%CKn&G$AV@LFx1Gl8Bmq2 zjXdfz@!>#qe@br0{yE+=FFtK@4%uhmjgoTz?%i{`ZoQ9^{}_c%H3_gRSuKoV9PGsmFe){Ps=;9G|mC)8wX2}STy^Zv>( z@%h*edLnzR%<1Xr2}JS>>}0#l+o{c)=eDE&6A-|Jn#oAp^T22tiG{J)*Oq{GLgUwqw(KH4_HtEVG=@JeqfVU%UYk@)EWcPn`!$7j zj52y3B2g}0QU3Pr+buos?s5<}3_8DE7NuC#(J}vH7$Oj>7!o#HbCgClkbzG-8p6S| zr^FJG1U%5)O34di;^Ky0d##rVL2W1vV6{Yb+q!k&jogZeVUE8>qVC$D?B|#vvQ?5l zYiJ6wEHcU8#l`hr36?9e{pt=4v+? z$3hOF^v;hIaPQe8JcqIxpO<&)$dMzZ*=Q??$h*>6zy}NF#%nr>(&B?|l3#cw$B?`LFKs4@n@o&lU9+utU zwnD-PpHf=f@cvYw8d@={)0XEv( zB4$653=RX(pb#qZtg*?AqP4mHvX3H8bQa%Xv!QeVl7o06wy36ayL3XeJ{E(O4oz+ z>(|$nvAQLrd^5UWR1^z6Q8qAE@kye@;(*d%Yi=6nR-NcGK=#hHu^h6W=sdChu zd2-lA8#Okgby!YOQD|{Lq?(UVj(i*1F_dC@Atg%cYGnI8puZQa6Q-S_iPkF6zhs$q zxv|Z4p@)^}RW9^7KHWTMzA6yFA3)eaQdl}r2}-Pjift5*E$x{>s0T)ijlNK061J$v z|H(FO;8t4(ROH627@&({-MW44`mBPvW(4ndpGpNC!!F~>@J)zg14GGOU1xv6GVrmC zKp|4r-;%)DAHcATWmN4y>YFhEocvzK%GB4IYbl)a;laIob@AWLmU@>pW@l$ht*xxm zIk~oPf1Rh?xX&LYl^M62P38Q9>)U&^|W`l$Ua` zD%7De-^JPaWcAPJp6UnSmy?yf+iuZBOkt6fQI+lOdWbVYO?wF2c5{2|SCA}xe|r`v ziAgA?uzuqSYH^}5)Br&}dF(p(!cc|4=mH7Etv03*NVmPpi)21ac$2u3Lqjq^!Tx34UP{0sv#)H0_qMtD`QcE=*DT%Q|cEO4Q+5> zyjtQRCx~65{b+}uRhC*i_hEg z))Ti$BDLJc{`&)7pb#h~lpv7FuR!21gUCIZzlV)Y5`-u)8cH|NW4ST@xek!OF+QK@ zQGn)K`-q)qvV3taRATCrL0~k|)_iszJa}+!tc1qzFz8S9p>bd9!-PsRJ39a&z!3x3 z?6a>{YG`T(hv}%RUtpdFx(amADB67HYGhUQZZR<(;83N*vtJYn_Yl{ZCDiFW?$_Zw zu0TL24-XF_r=K3XorO+BKtjm!+ECa55+gj<(hN>E={I41OkT7?lILytUnY~i^_0aR zT_rbzPJrS-)PBHeGS>BKur4kD1YO|bhb@KURbsXs2G33jT>f%`7_J3wVq!`fMY|yC zWvOX0BnVIpIjKPmJhsG85~0-08~DR+AZnlJgqy4 zA}U)8JHW(r@v>gv1OnL%Hk`rc%s7y@ER^M_Wn|Y5*`wZ+cN_0z7;5{AH&^y zK0ZE;Y5JDQrekwMX~Lp21aKkoshF4~G^XmAC6D}FeUmklz@cRVSooBbly+%Qkn-q% zOAC^L#1th(zqmsr?Rmy04Z+;OuV* zI}!ILX$HiYrmJcLw2J>|P#}W}1p-ZPy=1nbF)iM{cs0F<)==F_ImnXj5Q%WSN#U!K>`TUF@ z%^DDA_xoEGFWO`wjeS4UTM%dm6MpfY60ghEH3&H6S#7C zIKV4=L`Mf8H)3WT5gHn5=KnK8`PwncA}ZeyA$@_mZQ8aiC4Aw_E;$7S4MW2iSQTOk zwU9~Zk}?_}G5x@_n$~%hyWPvrRwB$*{J+H4h(Z*FzmPrn|Cf60Sf%jP>cjIVF);Xq znTAeWW8EpF>n_DmWkp5*wzf6_3`=3ah%=QDR%JI_%k1T+EW%Vgi$!f`t@p<9Vx7Moe$_iv{}gf zppM0k(<3Q0HOi-XAFL@JPpJ*;6+;ZTKS=u3Dxl|}!l?gL?l2DiOS#*zgA1b*XfCAC zo90TtrW$Oru^Kf+z@8QLjS`Ej5t!TStk3g@(W83;yK z2&7(f03IiSt7B&k3=a{(XRH7Sftmky=%4rRZ$c?#G9MWkVHC4Vrn`Fk=1mio;{H`6 zD;CYalx3@@53)9(J1T>0V$HtvmX4l0qcOgg8+xlM?)Qn-NuH)(_eAOgq^QA$p%H^A zUo^$sm=IbnWNSkOu~Or4SVd|%Ty%RKaUCR*td6t42sAE@bZEfv-{ z@87=%{;C7x^A%!cWks>rl2iZ z6d=$WdIW|%AuVeuw-7oE@chT9;}rlD!1E++p5H@CtL-@+(oU~`vZfXx$h{b$;ia}i zjSwi>j4`p-!hrFYg!gXGmK7vMzdt4?FBK4#zJy%&QU_Gy<3*I&OP}`sYW%PTRaE*t zT1ko+7+dE4b@xC2H{uMa56oJI*V~0G+Ts%vxuc+;k3gy8;*v!lAe6eA#y{1)Ce*J8 z>>PNi3r4$$`u#0n=>%tF^vESNAYO)Dn(Il%N`Ehsu_g!(LgZFJfbh};%0;sw5mGbD zcrl0-dqF!tq5-_*aSMjRf+n?`xNfX?JXj?}q&z_)2_d116;NiaAebiFb*P?9$VDhY z)JB_sg=ftfdkC)>fT|{CfMdC-I@=uR%Sy`1$>Z@8ZMVFWU6i zu>Y!nJmTVdebwQ@EzZu)@F|`BNh;nCS{TNJ*<&a~kBEn+ExfDONInC*Ce#fU)q zEg6Qlb1pSM{qW)B6L_99mv7u4S7YNB5_&+tgZPl0m%o2LmZDeCc&goed1*0r3asJX zPa(q;>wv-BWz`tT@d8Fy4pq<6vn+ytYp}mQD7)7QiAg|}>)pi1r0C=}YHzDL|E%9% zY-BIlX9%$GXu63HazrV@&~TroJ$xchQ1t!m0Fc19p_!CJHW3i0M>ba-GhV0Q;ZT3* z_tuEebqiJshHrW+N+GzmVV3<+qk>Qf@qP2= zO+ta$m_(+{FC}kG@gb`B$X_b>%bVoIk>bzk#}@&XQTBz%K4bMxCFx`MN|amd4KMG9 z85se5MvXQkgWXUih*X!A-M6UI3dsw^MF{xw=FRShQtpmyS=VD<9x`S5ttE!u7-MR= z*Bd;Fl?89zPxcutPBTfrDOC@Z%!uNR?QqNFg9ZYO3wXi%XZ|Vu$gg5TTue5g22)bO zKap)*NX{3@wKpJm?Qb=F*Y*YPsW*?u7lDq6;DTAwPf{0(dx|T}NdjcBZ+wQqA?{)d zAsx)*zzx83E;lPn;E9A=hcQ-D6EGBo)YtcdmqEnc|MTsmcU0P=!VoV#l849z%zW&6 z<0@hD@?+C=c7CyjhJ_b3Z{PF1FXkAZs09RGw3B*M%64RD)>g2 zS51s669K$)=U=+tuK+e@jocwX)~ho9n_hKE^NCZg7KmvS>Ez+zfj^BO!G$&n7QcUT zd}5;hrN=6T)|e?YSoj(g6PbzNYJYsd=%<=CVmHyR5>hu3-fO=uN}mW?I^_ zmx3H8m0&RoRo;hB2`+)BG3f7BT377Z4p0HLhhvNZ1EkHHH=_=BasTg!T;4)HlQSjM z2@V{DF%89=CvdfD7K13NZQ+L-fT;ZOTkr{fgjDY9ONmYdXQ!GI`t4uU*$=)lbV@7L z7*eXwf7AWx6vG;+`NodE0`zTkBW(ZU#|cn$>j#-wSS%>sK)wFqse<5Q7=)e-68)gv zLJM|i*qkl19GskZ*x8R@sjy%!a})bs(~|y=L{IhhaG#1U^zIx447(o^Vn*=>s)7cz zIDyH`Q@n(cmy1@|s!I|A^}&S8L?jQ@#>f+q3>l@!W&Y$a8nf_g3#i)NotGqe{x^&< zWIccWyy;^4YU2vRc>>xYTHwn-I5yy+3E-m51wkTc)*Prfm#ApVrW-?@#l?Urq3Q<_ z)vaHCMKzWWk(o#|^3nQ)dx3$07c!d(*&F7_g8(I8Gufu z4nx*pAEbBSXdaYg)CBZXEzC5&pe96@qYG-s5wiq7zDi7Z`#(m>gup_gs~ZZ`fN!EW z?_ndEQ~oD|;0UMz%DMmKi8;j^h$D@IO_+61ZQcI{cLM_TUEwMs;RKP%K;Pf&3ZPOF zV)0L~fM$cfj>!vXmMS_eCNJ(fe*befLZ87)V~14_95@gZ9fo74 z`hdsCM1(%7$1ZhBsHKSK-%e0A7KJR zI`Htw0~(|?X7b~eN zExo$+#tJ|m>#1+2F(=*Xk&B+nXb#B%A^R&@hygp1C5V>B8~@!?Qd<^=Iv51VLw%NE z8$pH0o+HeXcsbtx#EBE*o3XFjPq2#6wXv6|P<5tRgaz}p1;JEhB?&>nSKqC)dMC zkA}##Y4esX{nu};AW6z!ftT^0i3ai8@X&?G_%Rx;?f@R!{j2Ooq?oLWjM=zLargfH zs>FQY`nrwxgM$aNw6(8+B@l{lpv}UJHQCy=V$Yv4nXMa-7ysSU5LPh+x7#LmF`3d{ zkk%fiTx}O1W1uAVquxJJaXcdsMjU}K+VVdBj_fmqjwU$6fHfu@2%>i1`XLi%t>t6S znt-(N)39FE>hvP+;!Fxo7GMTs4NFzyhF%q?m%Y76a^lNfryT82KtMe*GLq2HI0njv zmuY}NDc%4l48XP_YSVuQM+-Q5I$&4a%2NVVZBi3)gb2xA9%AEhWFrm(Wi)bPOb$XX z69S9ph7B9Q%W$%xl{+VIm3wRkaSUUosdy=SBhLzLq2GKD@RA%s`>*<{uKwsh^|ihI z2~l6;1BfUbZpoJEGDl~Mor1adSLFI_Js^XjF1UlFQ{OlG0?f>lV3fl9$_5gyH_Uej zQN%Hi7g(CM1{M{y>T-vC6#MDZCr1|rf*A}qXC6l{#P}0ODc;%6;|_R)g|&|RGv9^( z33jDTTeorv=bEME+5$ts?HK>`sT2rrEsQCQh2pj@nyvsOYMPo4V1;Iyc-+Qa6?S}> z>^IIMN!}(5_2Bx99(jB^IlFi5I*t+>>k3B7c<5?6-HqG7iaX=tDh3p>aRkKFNW0nf zc8F3*85#Sd3PHQ&PM#E4X$hk-LDZH?nj>SNVw)gb0;5qchA{e2LHou0lS>wo-kqeR zB!VG2!OouCxx6$z_c6d#y-)73PR^x|FC4~+8CSkVW^>ln@8`jEgHvI}9w0Wzm2k43 z?qOXTTT9q$V$Cpsn0vd&HBuo&=y58cE<#*kwViIaZyMhiKkV3@3*X6NuW<24sHc|s zWvC5%UW{GCS*W4=X;e?d16tPqCR8|;7K1TXb8|CN+rq*k#TBVhe~0}jmj8w`n5sRu3a8$p%DfS9Zu@)gGf2r59RT>#WLoZ zdKhfa_??MVY@#Se^qAlT5E@ibZ(+cpA2&K2hf+cuEeu4QSh6?&W(a7f9Z-}AQjK=n z*Vi<-dDEt7NSkVGspysju5!@=JwW0_!nM`Nh>iEI?x4fvia`iX6y- z)h`m79^yo?HmIQCs|{X8q{v_kke&pwvQO5`U*jd0Ov*qzb`2{3ZS73J;j$1s!@{INM1?*=;&w~ zZi6_g0qcbd1gmHs_5w&vV0>w>!Yi_0TO#=y7NE^ukSc)9h|Y1CTlIf&4H?mB>mga-tsFIl{_FnV^pPk81^0?)$K z@Yzm8ecCc!a$qo2%s%yu+oG+kD%2bN$GFf|%7*1RbreaBV!K?{@ucjS#^~}Yx61U< zjHoSaY+Z`i$e=EGv=926c=gBrSpj`SG#dS<0SFXW}Q$4vcoX=&*xA1P_+3+jS`f;R#J zj-Nb93D?-&M~`;vj0_L+d9`on;5cV#X&D{1fzH;MFeh6Or%gu3YVh}KK|%EHt?WsY zLrn&N7Q6TCd6<}jbA4;|-4?U6DlsMJA?qZ)Y--w!@OlMDBQO5}!RL-TXBZbpv3fZ6eOOvy&FD7hdqD@yWUzUO*WH|n9c$kib#UI8u zGSZzpcifRoY#ba%wT%#L+UA(e9-%1K%d=YXa+uqM)p=|M=`3o-3>IK7&U0M%^6JJE z*&U5G%LVeZ`dum#s=_Xv)MkFGf)-u*kB4&56;l@T^YT#TSipwYM!W7^Xq>fKSf2fR zO{AqOqt&_THf_3&T5||a}YPV0gw)!h-}|(dIf~+H5g{h z%T}=63l&F?9*r5az}UV+GC6>>l+(2c_^D$^n2_^ z+PK;qg}-o-n)gNpr=BU~ZXapM=D9Do1Jddpq!}L#C1rhqU+*Q40BKdm|$quLEC=?y=>W7uAdZMl=&dwP3!YS`Vrb?f|Y_Zy;{@H)>XK0dyn zYsD{zZ&eQN1>=z}ATNP|gpTl5jVK{yNAp1pM6UEw&P|W*A(s9D)j>u^Mv5*w$&=e$ zTOl53&X@yt)(#Ukk~aObXW8KVcm`i;vhMQ@a4xSTy(ud*KzHiL@}=q*Q+L@35_5>7 z)U*C3-kli5x+C|R)7zkKWRyvFepe|g9b@{v5_EJb>#@B@U{A%d>=kV+j(so%XYAFL zl3Hoemgf=fI=4<@apGQ93T!mIw1~!)Vq#(j+bHPhY?YCUpK>i(p?uIXG2I3WHhG+o zz=g>e?Y3=x*cLVsku7pDwKocPY&R{6z1}$poO|@rC0;a#6>Zcd@UBv#LX|*(&`G?l z@buspf;2FR7r`M%4rR_0o#8s|)v0D9l{06kNm~wH=EQ`Giu6dxJb2Tb(|D!u_nDr6 zlIG^EB&)CG^e)zwe8VZ${{WV^tv-&ItUV3v?>(JpE- zE3rJQG%$rRvCgI9`l8*}i;h^L(Et95f4h#|3S$0gwh<@}yJ1sHL9e0RvSs)BHz08( zz?LV(cWr+<6(1YB24{y`2lP(NVqS=VJJ@(p4-$sORQ8!uZ!qQquE&9kzxc|$ZwTN0a~AU#^tyLay- z5q>eVMBnoF_r@B6zm37oMT2fna>oH^oZfad{?Sv1p`b}#6T%?j@)Qg+zL;yt4-v(< zzd3Uk&WLzoVk9?CvrY8+*x1<4(P_naA2&mRB-?%eZn_sPV8V6+@Qv&<>Z>1^d$S`7 zKtF6YytGYmN~}>dACX4pL*+p{s-K8a2^84}4^C@qBZs9ZUcmn;CsDMK&UOvnhuAgP zO}rYCv~mZFTDVp3g@@BXR~}db3PTg))H$v-qwo;*>oW}1cPnA@UrWe$_Dm2wnZ+G9 z!6mqw)xP}s_MW|%ZOF{W@q98OubkdrIi{nbK@WSRH5}Z9 zt+?Hd05G=qrXAw8xSBEjQGT+Ig1`|u4^R~?seAeIes%7kOX8^HL>*gcjb&#p^}i9n z5hp!g!q*@DvK7~BSm87|xWlU*`E}uFCGu~z6nWbVhmELJcNAdr&>qLeWF6j^dmW=C z9ARApgG|t2`CN_Yi|DA2#O(P=Y;0^K^d#*eWA9F!rSZpcIr)ZW(#ww@>0t3JgImwW zJ8XKiGXR-kmMw16uS_J$mc3`)1@`RQM>pPESpq>ktL0gC_FJB`7uR5~!qrISd_xM) zw016eW8`LHE)3Vkp@p#$^kCP_j=1_VoMrIC;Nek7hpeM+BG$_025sFOF~qjbCQ>i*2idA^QwY=e2QyBkGIId zgRkDdUk3efwWPE7;nl^-rtHR#l*NR3@l&yz z1hV)}VBktvp$T;I@m39Y5CzzYl$;y|de|DuE$#q61A4_zpRR=3`5Gq_B9wP`4GpbV zQmU5myZ{G|h|?4=#Lya~&CKlVtB#JMXFlEj^b8E2v6{Pid9N1~h+&+$Mn|Vrvoq~5 zWpOr@cjxaSgFi*n@x%g7j6GIb!^ovQgqhe`s4E$gp%|9XIi8f3&fm0oa}R(VDh!4< z%|Ebe(#MZ;h>9|zO?TgElD;5-90nK?++Bknecq}-NJt2|X>5bphUfF=2eDb_jEtI+ z4bn3*UW50K!SV_uu4U$+26%|EXsm-*CR;P-Vy_n;~Zc{U}n6H??Y&md|5-o|2o}LWq zF2~e^8=_)Ca$X2G&z0s_zBRdK7cZ_skIlnbt1ZS??CmWzz4+0bFt1^JQFQzEdg7n} zuU`Hph%=5&Wm?%6H;I}*2Vf2ycR?!lv#`fjB)9teP{)2Q79mo&o-f_PrKbji2I47gy|o;@@e zj1!Rv73OwZo36>@n>W`Hk1I&X*RitNdtWYwh{bJBXjcM@uOVxJVt-*poA>Tb6nXji z<=4#Sq|6DdMT!?(y?Qm9xOm~mN%W(1`1uau!4l~?ITkjHQ(LqNSJyLmkx4HRE_6&x zW?xtY15#4>kTAh7^ql5$_o_QNv)Ib~QF+?E)Vb+v>*``8+u(DzMq)woE^k!h4(e|& z$lY`U58I#xcUp_`$1xdtBfbYc;}~R3^>)HFGqoxYnY76cGsEkio}NE%;}{I@9VDGa z2aKN9uG-z1bX5;{DdqdJFtiZuHUyL@+Lv`GX0}OfXxCN+c*RfAH z2;hY_+_?q*;b#T)yo48hY@}dR$f00r!tz}F)Xbql-#^O2c2e$9Mhs&!BysX2P?Me( zqd34{?8OjD{XJJ@&h3NAsk%6e|LGKtKXoAo@@$75WPPZu-GDY)YZZ%Dm!eH~^MN^;0WN6rM>-Z;8cys(AfE8~2)Q6a9;8G!6G}4GPHa2d7#Li3G*Vk93 zyq3<^5eksVDr$Gsr@Qy7(p~?S3`5+q3t7JH_NhHc6K%pp9C!>J_>22J&@zLYQTLm76gfP8GO*QA^LDtH}a0BY_A2b+FN zrL`4-y|iScy}+-XYJ2`sD1job3nIT@1CI7KI^sC?7M#G^bZh;(bsmL--b7@mv8r3Hx)Pw5Xz}tuL5f)zXc82N?yfG9late@=H_Q}N<7L5>LM<4S)1(s zUAa{abKzVnfig!Rf0ygDXl4StYaWD$TUtrJMJF0fk3w+d+xfqW$#2%RZIX zvon4-;yr5*u^+dIgX>ONS^4ZY3tC%aDRRVKL{?VTE7{ILKlFZWJ-Ixn z1Kzz#M@J{+eN`1T-Z1^yGYUHeXvE(3XasD`(D38rH|wKOF&XXk37Kb z`*`kDquTCG
    UxA4>>ofPg?*d@M0r<9+@nG%0Q^HUV^l#Jp6ub-tFVDcz5@`+qL zZi*r!!P9(lnPKzhsI08|Pd+v0KDD&SofD}%tGif?sE2ClfzO_3DlPTitg{#nQ2ebm zmj=s95Jni~vp&3evzmBFf_nQfPSJX)CJ3Cjyg6b)v;-=#;CuHxgM%48Thw=Nva+=m z++E+>-~X!L=c}%nM0`wWaw&IO@PGk`uDa}}Fi3jh>A5Q3X5bp6hL^8id7Kl? zPf94U#C>DUh3)Kbh^}5LX3w7|>Lb*VM9POytDwUYVs=g#C?aM%JnP>~LV!Nz%`h=F zRZ1ubi<~_3)iyweqQ*K?ml_q2U{p1(J`1NEelIXEc?r(B1At@SRo-^ zA@4?yN%-k)x?o|!@AA+*SuUi=mNJ1hE-g{l+?)@-HKyd=4(04=jGb^0z?f`}2De5g zs}XwK=`D&)`al;~9UY$%ZYWdZF1#D~GzSPIHtWR6llPx=e*f`9>K8wz`-`1TJ%}Gq z!qXEd(g%`iH6=tkX~Ee}?+|kF5CXdhE8D*AcU5uzx)TWEDYdMgNlJYD35K&~<@L4n z^}M{i7gj{f-ShLKN=`|kVtgGP*{wJ-wQ+Cok-UPNv`=5T>mH3fIB7mfvt!aTWOCOe z4G$l^NP2d5&}*y7UB{0fFRZ}&uXJ*nFIYOL1U^*X{P@wM2uz;)>*8oIK3U&270^i> zb(CzwNW>ZlEmYK&0&Jeky>+w2FPecKs4!P`2PX*WVN%7UC|M_$8WWyZpg2A_gPr~E zdybYA`KC>q*u=z`u+({ulZjQW`Q9n!h+;q96EV~xVj?2_DT=X6X6EMY{7HlHo>s$N zb1NlWG$sU=6OZ16=1_~{SpKjSe;#Z|S~FY?zzylHzoSr$c&bi^MK%51-;KJo^gJrx z-;Ek40s&kjA|mXZn5DOQ$;C(^`;K@J&wBA}%}!63gq4bkDjP@b?GtPG>F7*)_K*{j z)&(1YT9lmoiZ4wSgSBpNW?(3PZRY(Tsi_PKoaU4Aj*c@%^gKs*GBJfPBnU}H2S8Ed z-ki1bsLxo#=1?9ku2--XMK8xe;0k=Ob?&H~i=CZaMtbP&+wxKOfUw*m*s!OAFCi}z z3IR|x4uEZe#AAR%CHGfa11KDKbQFctjgFOdkGYwVkq>@{kdP?e5>E?QbbfT_PR&_; zsQk3_^j@GHpK*-rH69&PcX@4#_jOu=wxUv5LqyQcvpSNWLY=!+HKww@eiLlXM{!wQ zBP0A|ErV;@>Nl=ho1zq{{Iaxk4X}GZ6y1Bddmy2Ebr1UVfDhh5C4nJFx7c+XbSA8d zGyqeF5LBt|fq|P&BhT03Fr_vgKqDXGVw9Ae{Dz>Lktbm)+NHw+f~;YWH0inW;2jBp z00-_*^l=RR;>a*}kX#CFNRe^~8bkFW>XV+=#LzE4vQHKFW?X z=uEtnaZBu}kqOzJUc?^T7~ysMFam&VaWdF`yjS6GA|ztdPfNW`lrsgOVY`O6ni2#O z5+hA<0v>t@q6L8!nqdzPvY9;WW-IlK`R>6aC!W?dG6~s^S@i#lZf;fpnN+!H}|@=b>4r; zZ5=xyVtTdXQmzyFThVbp#vK~=2fpOp9AN-}SVJSGefqS?Pq5^elws0gZ)azr6(o4` zM!W&h3Gqd#s-dyt$)`NmMN#N_`~@jR;W%sarCVA7Xpn!EtF$jDwh9%)qw(4H^pj&Yf#e5NjQgyZ{`uh+WDK(CLH3(=Kp~ zVEGl)F{s*)7{tS3Cpe%T0iKK4kAzN4!xRXZ;Fz14o9h!E&I&Gb;T#8I6h-%SV`C0g zz%|kBKt==e!~>!_CIM6KpyC52=;qtVGQ4?V)xDB{E;zOviqlkPIx(v2a1IxcdM)&% z2TN7!v_H*DHLW@6>35{8gS+$QjvPdTc@+G^Oc+b7q63~< z2G`GCoI)n$7SCTaG<^Ts3Vc%4E3x;4y!=r#nw?5vzQpP92JYja21EyCu##6)EQQ*_ zcD+VhA6L-Y%0%St3N%BBGw+U=m*SFeY=|5WwbI^sT@okZlDQ)aZf*)#?9DH?Nt+)d_kg|t=!{zv z?L1(!@4$gNu@A9m#K}NnAVFnX0i|B_Rpi!@ zc-9#!dwWd79C%o_(y5g2^6|x-drZlG{UvPLOq8pV`cTu>1F&Pvcqv^0G7Q%6RYiro z8P2+SKYX~EnVET}hlBVi9^kdwzH~hLghT?3#o=i}cBbdi6et*Gb)8v(_`Hh4*6CnA zg&GNzDwsMDQ#uG&SYNbqX~H-7@*405d=57;fr`TXsJ|g;GgM_ioUuD~`m|sHjkNiZ zNaYioj}dNQGlyfx$Y6x9#?wTb3IDkQ29~ugRh5-g@OHh1{=d(>Mc`9wYwp`_+H9Di z_hY@F$4M$E_#H6^{0E~K+G4Ec)55%Mo5S7x5bZ>M@o`&aDRM4%6^XW3>O9zyQa&cl z0sh!%@+L}DH#a}tb@)bnohrbejm`C_C=Og;dsjZvP<5}OzT^lPIz*edpt{x=$wH@8 zH_|~siXOEdOaP2w_V+>ch^GhfAQXgy2WS0Tao*wO`aLh)(b>-9Nm*OO>@G#MqTYVS zJ*d6|xu+v^!Om`gb~-54UTyXFii;)o9Ewt`C@-hL$ry5K>Iao+;0ic^i@ER8fm(%a2hZcsuC4N_EyKp z{Ui|)5drO(%94^*ka}a{#Wwqn?}9W!}5+aV~C))4oRl>&K%Xc;(N zuKDPi2JSGp8o$UWn#ewxWZ6i=V|4N2)9C2cC_9dBHVw%vpx0|5e@}dC-iYUxj7?Ab zL`4~xF>fadon8;-+kB0hkosAi$Bq!I1i%L_MY7O;VTZPhQRQlkMF_Gvv8J6E&5+sR zY0 z4nfvkA1N}akH=SO9+o1YsDIjy5=&E10%D#5i_mSjC%Q1p$g>*`zO)U#OX7$T#dDZ1 zp5hTGl=*ampvqqA-R3ypkEtgy<|VoU*=OSMB4nR`4q5Z?_|a%K-BYKwU^cbYyWsXZ zc0A?oymAEJu3c-P!>`FsQs*{2lH)C9J~cJvObro6knY!gnoGv0vL86G5%ZopisyPo z&ZkFjZou3f4T9@aM4015{|aclHUqU@yN;qz@2-s09HQxq($v%Q1Fk`we1?BtJ4g~H zJTOLgXx=8~L;d}`lQuME8Yy9CBaq|(&gR1FUx# zrNR?B&*E83{hh@UKmeb2QiN5{C`xv30RJ6+xLCR6p73! zB=fLBh9Vg%GnqnED2WCoDI|(ihBAhTN+n66s8l40GOSQaR2oE4N+hN6`yJN(eB1ZE z+q-S+v2Lrb>pYKP-~ZF@+$hVsIPB@EvwC%(2My(8_Ts^lNT~WpNekTjS7n}0S%Jm@ zD$T#ek&u5RS87b1YO%`nO>grZJ9l~v~6hl0niKW$@V{Cl6mxo@*60w3pR=j_EXdb&Ns~qW&!^^u=b+>MfqZ9#=AM+vh z_HFGID|!G^*;W^6fru{5+wJIRf^lI*Q99{=5nT@+_FWLRa$%v;Bjk`-vr>f72)<-UjL*+O;hL6?boMJ;gfT!-uO@cXpRT{${&l zM+#4VoZ)IPF2qF@Ty0R8o2!5%MGLcrD&qDo{U*4j*o%8KRIXpY zBZO3TU@zW|6e$}kLr?(k5JHw}eBK|CL}bPysF9YDNjcbU#$iapKw8Ti-{xi|kLuNV zRJBOCl~%UpqjKWG_jDU?EEGVeR(y;KO|%r*I>lt ztwIUD`_V;i3Kcy)y>Q`jdi!fx?^qwuv{kweZ0Jq}M=;u9FI%JZaDQ z@NXEJd z_+nc66|3&@DT=W<%V|G-i&Me#SKC%J%AQE{l95UA;^vl53l3@?5dHtvD?1CQ8`|S>U`!fY&vgvya4V5~GRdNS)l?ipnyI5;Q=axTP zkZwpxaA=OlVY~REnkaxiI!c1>oxgKuB2H^}5;%koi;}V)#pofPpdh!AgQdaLs+v4% z$8YY)2X|-xN8S4{6uyjmrNb%<;S7sgCnMuIx2-iD;@PvS#PN8l7;ll+%+{ti?><~! zVvIpNwMsiQ?JrpTVHFt!KM1rpWo>g3rSOnpwMQAI(KT$DtavUJdi~xh3MXQXju)pK zT2#ZK60&MoEvKOX;4tAt`=2<`4Y|wFjstf~P|I^atEDQ_#diOSQN|U$stKGg@u5-@ zpuLZ9+^MW}0H9|N6}wwdY9^E8AVg?e^W(Y`IFLp(!4Xk~qL6&Z(=Gb;%?qxSn6ci_ z-=P@|qupj<6z3ekuQ{qIPd;SDDA_UBTf(>9zI%7eX9x@1N#h!Z2L1l;QYg=&!sV(J z3Y1aRgcvCshH@(iilmpl;&@{Tca&F_DfjvBSINn3h#oxb<<-u%G3^Y?ey#jiI4v5X zRBDDOoF|gIg*$?Sf&|(?fB%Sb?))Jwj>BD1_4T_&BOr8ma#F0E-9!SYk`S=?(v`Jr8N=k?T)e~dlAeE^oP^bA9v%Z! zaO=md8!=+Uf6&;LEn7Se3Ps$y{~BBkKVYGayh6dJBIh{)RR8`bGM7QLA$%io>i`6M zW$E!XUs9D{29FiU5fr_Y7PGBsa|G@pobZ&sU8vtXr^pV_=(TzC z=D9O^2*~DNH@SKO0(o;CM1?0Q`uNcm9kdDAyfi85cHNF#3%&!l&6^evL7*l=NGE>c zUV$D!N{O=*{z92BpDn|p|6lS*Pd|K;8*m1Z;koA5sG^VcZO`Gp{7}l@73;8@DrgGq z=FV^L4&Z#Hc7A$JsMi`yNEJLi;tr1`cRxHK3-l2C*n|*kLA`P8tUOkWw0IT=EP&Dv zl#evceORXFr)(dLu(TbehpCbj|H7e%w)9>?9feZfokBt~3$2j9V`)Dj(}TdBAimzj za#TX=_tmb_B&qE$xk0C?Nay?*DOdOY{k^!sp1InH9)^+xS%OyOMa&3YBENQyeV>~f z`!hojX#M^xQnQpHL_ShGiU-3DII{=~X66JqSRuMWi_xy#m;0wri=zHGU6?QOGt0iU#O+Uc+IuXn{HQ749{POIr)aY#%Q7IYvhPC4)3I z`?GFRxtOFwR#<#0ppX*q7eNOpKn*`A**8L(h=;wzPa`DeCQSoSyjGyNYaSfu(|14c zx9%!8hQp6^tl7NvLqc!CQST+J0Zn3C5{<@l_;k_JbN*MElJV76Yim{dbuUHrt`ghI z+{sXi#vBfUUvX}()o;QwflOyA0=;T73^tM;*56gMU|m)i7#!7K@7SLESPej3)%c<0 zK4ubm@{ywM&7Hk#6u8G?f6achsi|l&qR6@f^ytKX+f9_vkNh34iosWepf2j(Lh&R5 ztL-Fzt61DBk)$%B>Qo*-UhY;>iw0;-(U&iW+spJRLXQ3fL_HEiVZKXibC(BVbXQ_o<1Mm8ZCDAUi3Z+Br8?s+;b*qjxPVOp8v%O-{D}F|RZ)$d$?&U}4O! zn`T=J?)RhgBD`+@!Vt^Viu4R_{9cxXZ|xe6s*0!2pFhGv6~(#&xA?oSX@G^~@!QQ9 zL*K$z?s97q_e@4YCjwyJ?;+x<2Y(RJU9lFeq5!8K*5=Epsz&M7>B{!hHf9_LbmBYW zg`)1gDF&)HWt)n9!?|8fl*SM?vp^(w=7`o`qn&`^z8oiWuM=HIWMt$+bO9SocZEJ< z_xym=G@-KOU!!6kCOj2=3I(q9gY02gaw(AIdj3xXd!>j#;6MyG7Qee41X2pCrjiWi z`m9fz*>V6NbaB9p0jw@@Mr>xV3b0^orz7vY|jog%WRj*|QM1g_n< zvGwcN*u(fM1e5VsJg6A2p0ysv&IEmxWIsDkK3;vmD^jcu5=Rvj9o0=8rX5d+I#YGbAz9&CQl&+Kc3-L?YgBuyAlPVA^DmN37 z@x;A-#f-mXZpE|l7Tue3ZHUAgJ51G!n~!motmTSwB#Ryt1{ojwstN?P z%_+1wC6L31?%v(ySrt4H_pXnt8Pk9!*VlM!2b!nbd=)8{!QXtYMG&~njo0!Jp_?sf zwrqj2u+qDrUJSmmiCxlwGm8~J%crjZ6 z^7wae&jbXF`%nIb5Y6s-N9E@xX zNo7=n!aW(kwq9pD51(a-KM?!x^vkwIcj#p`w8=q!rR}Yi|4U^S*A1OYv-PL zEj}W6e(X8!!C^qIe|;y*;1!!kd+i%@!lk7qU^gBxlZ_i)#pY+{^LW>8Nw4Y0gL*4g&0F~yYDchy6a6v~Z0s+^~xW&g-c6)6YPw;F9 zc*E~@%I&xePo6r}hVqrJK`lP1!Th&qa2Z=P0!z1?oZNm~edV%E<_|jLWM>ys+L7|z z4(UrI@=>9bYY1S!gM3IU^Oq$+y?)l9jG#ATxf@1Z(p14Ly~i8rprJMRv>mYbLlUK{Kc;@3ClD6V@! zk7!ITOx^Sc=&6Wl5zI6;c;L9aPc7xQ8GaPD&G%MFZ6j|CMr|eZT_A&JK)oh@Spy}# z9Y?fi^7>C%HfI0j)vbxzg?6BhUmaqvUY*;=87BM8z?oEi9>0%VTZLEm>1bWVI->e` zciT(`i-_vJ279sMiK(;sxh0D;r?@CLIR=$!U@d-nudjD9&z;in^$|9a4XYMdaX zrUyyE54j|bt*m5N3{Vp_$NfWn%SN)I>^^s9MF~=V|Ni}R^H#guMc~mxu-u?G2Op$S zn*2E!MJv}lT(G!4DxB0 zgRi*Bk$}9xw~$SvDw6qX1NQ!0AS7_Y+lD(P=9~+1aqW;5&l*|)Opb!Z8ue!q53uLj zB(f0-2cLLFD5qRwO!Rd!RP1r$LKe-%%v9TKLh3N6bh|O`atO#)2-@@B=3gK_BI zr_b;YE~HHR*6z0WO{ARTBVvwX1Gw>y{3RLcz`kFsf58#%@SuZ?@?*-rA+R4Y=ipYY zngecxhxer4k=lR1)3PrG+oOZ81eLB-_wwWc)yW9t{v8(sop#2&xjIa?qLGXsz6xS22j5&kk!di?(-3S?sYRM~|M)b;1D~{adibsInq<@4Xu5{nor#-TKBxtIBc21qjk0UBkIto=mUD(2wmU z8TWQ=JLTiE<@HX$TJV$!w4I|E;^!cR+L=l*x$)7rzTo!GvkODs5$;luwinnqh#KCY*^y~=vr!zpw5C)aCc>Cwj+O4(1eg+0 zNw@PDD~kQVR_GAk)Q}HQPkIHQX(zC_ZXCHdB^O5kG7R74b6Ik+r?e( zXU~}pBFjxZVF@spoc3Wbt%FNML~%^=XT}>k9!z_qP<*#R!>V3)2Lj-p+=0Cap7N0z zm>{SFskr8nA2dmC4Gzt(d@9BxOkawhVt9Hhji>A$8=^U+m46*71WSHG+pDdUXU9mdBWiD=`Px>;WrdI(T{O-$6sxZ*KGop;VAe2)uKb59BsLVe9jxD+ zslHhH34)ZI(2)YYqKFC2wwWjW!@NU0&Tbv$$Cb9*b&@yKilhPM*(t@soyLBQxGPI1 zUF-OofPMpKP_T#@RvnD9Z-r~;cTIvD{czdkUa3dnqzy8Y8?U|(^|(rDw$`aZ>P_v2 z8uZp7*5yh1UxNCng@LVnnF!yu;{UTJy2vJ3EP+6gBRo?MxNA?IACc*jL3no0s%iSZ z)T(I|*`{*ZljNQCHbe(IFI~_0K=d%~x!=d}G1BHrF4BP{0Z&Bb3!& zP@e}khATNEyg9ed_Occ69uI1!# z6Ucm!Cjav|GH6p`M=?S@h~7$MSR@iCpbJ9nhoo;aAK4y6QuD{-p65A2CVi(7&a9+o z{>LC%8UWL~w3#_`LYiINaeg|d&Os%YrtSj0K|Ky?af~J$YwTPDd;!!HQWAmcB8U5T z&4&=RD^~N*g6|Y%%u_lW!8}2C1_$&2XnKOka7cR2-mYJ71AI39&fAvROtWc9RBRk` zTCX_r9|?uv%S!6K0^>&Cl!w%{8#xp+_tCcqgqC(*Hg?a8UH~o){&H*cigEKUSr#w)Tnl(iuni`^j9QzDZQ@(#i^3oiI`h!Xczl0MOVF z3yRc`AFa8)sZ;5zfD$u+!|O5cg9Mp}zRwr#wCji6w*lh8b?52xG3 zhx`Po_rm#a7S5+MsAQi-4MC>hCzr75S6Ize^_wNg76hg_J=gV@0t_Dfn*A_gg zZT`YWVzxv&={VD172HrpJTK^3`R$v+)(z4J&{$o*f4{#33)^^RZ2Yq(a#rqYI!~5O zW`)B(ezR*F}lG6XNs<2B6O-ts@&N?SF7_cwNpl7VZ zdTyt8d#*9hfAicbD^bhJgg{aU0dU_t35leTN=ZZQnlOA7H2j? z0e;o&Z`*hunrD&luUo9g9P~}IjpROq6>jesNnw9>-@G?-c*ZcsBS(!oRm!N31sWp) z$?H1^-!-{-{&yRsr|l%)-bDpx?3g7^qg}&-=YHojdY`MqsPW0N5>YN@HZ`0T!&H^? zYy>iMo9%8D!*R7%5P4tAlN!!$=Y&;6x{Z{L z?=1SSFea_c+v|$Aq z+KV;+-x&cad2!o=te${^Ub*fDUgrIl@i|!uN2ep^+zW@IQCP^F(jgK0NxrXy ziX+_a+S+vsc3itx=+e5*cN?q{)yZiIvgHhzm-^YzRn7qJ-f3gNztZvf}UlHHFbz-{ZF%YV^ z*Dcu?BSrBYMgFF;Tg&rpzB-4=Qt@OR&VM0nj47)@L+f~(bq?!vax7P`)zcpn9uXmY zHSF8o%4HJRu4W{`Jb?uqDVn*j&2#QtpVIGYOWlrIr#pdX z3$wnDLJh*M)$zqe|9w#f*pT3KE#Bi^^Uc=ZceW55(bVDrn9kPS)pYake}uhS^!8Tf zI+u}lXBQ5`NBo51;!54T^t!$4zF*)uW}RJ!gTlh1z_9g1V&ieok1tz0wixW`_;t># zQG<_;Jet^j>!rlB9=cxs3c(p`PVe^FY&Xhx_K~aWvgCC?T6m>44p;cr>9^~H8l9@f?TIGc!|xsMLebR1mYWwg#D-A+kJXN0q{?QH{aGwKCER=wo4Kq zsvs}M&Wt=aP6l+u!w8qhoHnj=RZRvo^z>kbqomKPTh7HB$m?%e!I zO-25hTmtdMTsIrNR7C-Bvk-(ougI=Gy^0(6FqyxT)(qE8+4kJlkMZ8^c`OqeQMx~? zE#zDB9pY2~bPwIFl7 zect?j&UiO_|I+WE_oqIo?yu=MwyniXbRPD0H-==#WXpA%x&L|>gS51?9nD_HjGvaNBXbZtlyMxMdob1b93V;E^{X-S=S&JlmeGO6 zU)}~N9F@~#$Ced%-v=3taK7V@vYh6>uP$Rt$CTFv`r66v*ul(%4u!X7<%!h{~cfv#rNGi6W<9>7aR^X+Yu-%X{~ z{8f3h7%!$5-glfRcx2=kLeG7TNdH{BE54)4l9XXG7PZDx81sMm~)QB+*!ry{6qIAIyN7t8HCJ# zsi;_VysW5bP&uX|SIVzW4V49nirjm`b0fIm zayv3X!KD2MB!khhT@c2II~JwZMqiKe5W4BJRhn2k)j9xtWCE z)7vMxTXS4|{DR{pRaGyiyAU7g?L(q&^7LH}4rjZpBkDB%S&a`M*x>Rl$nC$p8s~F5 zYsM4;QL7uM>w}JeN1Suo>~wA+as;(C1L-%PRX*u9??>T?Vbn}07^NhTEf9Yrq!)$n zdG%+~+HEZ@^Wy_V_Hogx1K>L*!Yx4e01pvK!8krul2utIOxJ5(0*ssxB`s+MbhtB6 z(`21H`zkecZm$AKx%T#jD>!tV0*BW6Pd)_jbWN$X89`Xb%Pr0A-M*Uu=@iujmp7j^ zNK18o-~!I~%+dRJ33#AnKk(0@ffd!$!d~0#AR0q_1n}{rtINW50SL=}n-mljh$c;f ze$q#Ap7*}3I$6zgYwBd4@86*pmbXh@QE^d=T5P+peM4OeBl73H9kI%$WxIRUcdL1C zNi2>jTvvWA_-5rU_;rK#Bjn}fjcE_+QNG5NB$Qstn|^GiUx4}?EB`|^nD;wN>8&W6 zy5dE4=?`5Uram3zD<5$3^YJ-E7^nCT36yvuCK<=6hKF6TS#nb2ZBb#hh=OulGBzeL zYk+=OLRH}XwaXTKnA&gVrg;iiyX=eoROTaA+Lgp0asQs2OOf=1`ZqPvpBd-Rw}-Su zb}YA4B~|eJpgr0{YJ@pOv9 z_jq5%8TY3AjJ;F1>n4w#XZm0SePRBNu*kc&hflW7h~66Uqh(?Gyq+s2%bz?ReEG6O zBs58k>Ek1AFUBKvV?)wFgqT7!O93dmZQJ+NYj^5ZZ!^E3;b7_6e^E`@s9MFxtpzAU zESsifzjX=Dd*ryluyC%MTu>NWyoeA}Ei}-AS@`#&dN&aSfKr|iw5F`~2QMCUajq&Y z^*~%V*>Sy!!@z>oK4a#T-(5Z2+XOODx?8t-91n9+m~W&j#JcG%el}q>QKdGwQg8YM z1Z=o-t}YtwfG`3B;KDdwuK4)3hKior%Ng7`)0{K7xauRElhse9G!FMPmN6&L5njkf zfR6k~!YD+Xj=`vL7VA7bJkC!r>&!+v3`N$&6(&y*?;y7!-p_pvM5 zvA^)jb2di&v{Q5u#wI4ovf(bfY)yqJ!s+Jq%@OcpRq?maO?9?Dy`ryq$n(dytW|K& z*lD!fj@BxF1&d&*g&C0Y|X3-(z!R=(RWqFWW|SN*_;;$bG&V*{|ckdN!_)jEhah3b{9C|)}zs?T!Z6jZpau|`uhHQLz}@zrD+Qw);F@K zg{})EQglCBDzj_JvQ?szpSN~xKSV2`6O46o@AA}<>UcS=OImOivB&mTtrY*m#~pG} zz3W_aR#N@xSVcUuba67i)NQZCK z{n1OBDrv#m6VGt0^huIV+<#2v7X<6im#mWYuPq#xdcNr6K2D9vqfgv!TG;f;bLC8^ zw>1U^oo7sAQ|dYGibqyZm$n2^8`%?zM%%&+%76X(B}e`w2+c=`SJ$h7A-;>45BgX@ zOf;ri53htc7t*<-n|H>xQC{t@zJb+4ooiO$UlpSE4Os&MB7?T~ui{lLO6L=ik2G+^fW zy%-BuQvZ6~Jyep;*n>&$mc}3FY%tnkN~0F!uu9Eyn7hlr%UbIpKjJ-etq7*5$jL3)VCh*0VKqeqB6`6@u5jd}5i5*MND?4cvpy1k|7l`4_2R9dRwFS>9gjl8!1V^~0sr zs9Bl4k}+jP-lDZuGY9S48&s~)wRPWEG-cI$7hnIndN2coPe7nNdi`2%+x;INH$8Pk zEuT3&CLsJawN-8x=lY0IeV?P^5SgTV!G41xrII!)5sG!S@9F5HybDtlQ~;w-P#HuL z=xAS_wV>pyeuRO$3wSv4wI?W@A{iE*p|tDDzIzBUKG{v(pD?WksJ49y<-x1zF63d% zcCne5T8*sKm>Nme<03|Ym+do!pq?ToS+l^o(YmS@!asg{#i7#r$uCGpSSa^&)#+!O z1X>lBLszJczT)l;ikuB*Q!g$ITxQH0&$o&Ufif_C3iSZuQ=rvek2 z;*mS~Y*T)tzDV{Rcg;~iZgKGV`xEN+0OTq79GO{#M9o&z#14d!UA`Kfgm_9)ZmF*) zCUt*us;w^8fhrw>lz?-mo^Z5OS;ISHz8WPA~K$@c_w$?3uwf+GU2WC*K~Z8_>zbO z0P9DItE)=d6mPR{Zce378XA9tq=m84m(HI*47hc8%r25{jc2}JEz+#9FqE#}aDVry z@ULwpurn{Gmu(y3JSYw=ezHStU0s>~qUH;_(#jE7NIMCIIsV!oUowUWCeO8br4DW; zkzyoFv+-sACB8L7GwaLBAp6i>SiEfl=}peQdXA(Mh?L`ssq!g2>lcYIyH{5qT+&qH z2}`lY)<*0Q6vM7giGQ=ZXq4idg~xy`F}sGuJvk`K)O8nEIB4SjckjDl@ABJQLDO-R zT^ebeCg0PjZfjVL_Nb;xREXO;-AoiLw{8DGO^>2mg-H0fi*nBaoqT~~*??zeKW_ED z1)pg@HeDVk-_T7H`o%N^9^mx(H(;g`h>y_o;s|$GH}o$Y6njKmEIz0QQYDdpLlf;x zH*S=d+!V0Iv59P1n|hY->=eQ5+r)7;Uqp8eXF0%$VxWBu!>&e{dPPCS*+FkqjPNZ) zOaD-ohaP2K&n}58#vLQqMf^u#L7T`Da5ZaN)IcQU8HOUMTR4FSse!o1yg(w~4g|$2 zbAqqVhceO42Tedh?7ORPtxw;#Q)mYi z{Lh|!0t3-LAPSx9Z8);qkRB81_iwiH2YJ)QbHmtojpE)^G1Yg-eCc0wW8m( zdm|3!bE?dO64QFsa71QoX(b7~>?$d(eY#-f+{}%#g#^={x^)n3lP&TRTN)~Y9GOIN zl-|G#zl2>gLfSO~JYqJ>i#QWO6JDz0GH+kwuw#emoz3YRp^QwB-SzF#NDT=uHr@=j+O|0{F>%$+?*N$XY6QK)xgbko`Lvu@&_Vs(rJYI>;ki=JSJy>whve`1F>?d@)zf(|7}244 zC`p%$Ugb6C0t1!3pKS`NiwLX>QWpRFi&YHR9HHI>5MU;Dm#)f!3qfpdHyeb(_8h*r$fFgy%*cgva`}5OrH3T)X5JbW_|S zMy(ta$??8mVoqF&?~wnsH}k{dtFB8uR)c`$j1{kEE8?xK2>o44&SLuWP)&VDAJDFZ z2pJ!y7N5N5@#OoNoM-iAY4inV9DReuc_AY!+uKX2Z{N_E%0Mwh<5@`*MYr@h%Cc>- zAl|>JKV=$n0?LGLV~x&O^!aNohjUO@vhWPok-9 zZYHg)w?<%+ZyQ#9F+6;X`hDkm-E~vXd}wVhY@KXkmA&rDYx{o4Jai4_?zq<2e^jgH z#L1J*P%Rh}*S9!uS@it1T*;3~40vUIf_;7mim=bxJ{ALzv&l6yp^6)tHqE&yZf;@s z&jC-HoSUj~e|8e7g$HZMf4^Y3pq`5v1UmBFwrk}A zG}F~5>n=zl>7yp5%8LUg`*_9o@2}QH&cI47VD~Zq{PU?Hyx~p2%%#rK zDyaS@^dG+J_|;`GMq$NGMe_^{6e=*%1SgHDJviXHhI9Qf)l@MTGQ*zI(MD{|c_5gL zKVOWCmpco7%9FP8KCTZ^758c`r_4K4TDhNWdu=f6@&kSC1w(x(cIwN~3iAS&NlRtR zI(VsaqXcZf^~WW4Lh3uwtkw@PxX#p}GuOJ*9?ZC|(b6(EaM|HUj@J{eK1gbEtWMc> z{rS+zM(gS$oSA)ujS4Vs${Zfs=)kpbBE`??USVLcJiv8e<-7f z4>A#Vw(Y=BSpb&&s8W!#wUooF%L=<^5jI8w;1GpSLf<|+9==|921Y$5X-;iQ-Z532 zur@Pl53Uur;lUR~Qpq(Br1MxbL2g6RG)yk)vNP`&EDPN^t=dAK)|JZYNr1~`GZvA}XhJ?m z!q^^v8^DWm1wd&LYTw&g1a|H^AR_ZmmvD}4FF}I0bdn}k@@3PEnr+yY|4f|dtvFLz zIWSpfGZ%BIM~#)@3SS%t>P?hrJ-X=ChIUJuIBAlIq&@awrB_sfr)QIa=Sm04PmTB~ z;Z-|Uu37U`1Q1R{H2uw{9i)>xlK1@2pojUS2`l|S$7#X-)m8Gb%BEp48ye%#9Qbx1mI zaM8Pdr7UURw{_{IDH&HP)4C;bmLGQ2VX(p$D(~L9Y29W3ss<;Uk$!R}d|05fIxsDm z*9@DB+1-*<)+MZ*ls>cNM>nnNV^Ilpv!@ze-`VB?HSf_XkB;S4AAPQ$J*=9F0P!8! z)laG7hvo>O&Oc0(8=nrwadW~THO61W(oa@(^AnAfT+q!8H^J8J@}Q7UBr=0}bX_e) zM{lFZC5sn-@<^YC|YUEJNeFHQ4rh~aRfQqs8R#I$YKp+jfO zJtrIdh_^cVe5NH{w?_yMLRUBL8()D^%$%8%le0zi#oO!EZGT!VHvQ(3w4Fk;XY*AeTs(ggHM{kUGE`{hMus-X#bvmXOy%# z_r`((qm&I>AnmJ4FC%~q)9e=YXL}{14gZ@F5E*IAwPkH5yS_X&jXFEN7^hYDE+i6d z1*kY3^JU3JHQi-0>KphrpJcmpAr$%NbjwvuUBh(gPpX}l>4(?RJ*{Q9fp@IVygItP zs{WW^E;3iPB4Pet-oe`6OEq;CsPKnQ-Mam?J#sDJkh{O?+=a7e+v9Pma=-?Rj>lJ1 zfLADaP#E^afL8tM*KD+&#v3;V9sAfr_RGf|SB_xY<7RG8!99zR8HtF77U8QP*qwnu z2Kbyb|HuMM6Hu#Ucj<*Kwn#!^-jK6X#1Tonkh`DX0CFC>h`j1?)5viF3z(~=)rP00 z3j2(R_PU?Q-@sFaciw{>-%S%Pm-@(^Ngh2}J z`7q=<9?(a~BW00EE1X>_nmR3VWehsZ?9_pc`v+{P^)gDR-abwkF+YVC3Mi%a$*115C$38D@0o zzd!_Nkhb8|Sc_c2$ibFomyp|pXF-|&fsq^{CXGissiBLSkI`6htAVx6PMOj8ZK43I zC6QP>g~Cc@{XmGuQ6j7j$?j_kSvX{Apd8sHDe@_tTc=K*lu*EssNE#xVueOI;@CatH6t47KzuRMeiI=Y#7`gc@>K2p1i^ges#<*7Xh7EeZ%YL3S{eURJ{d zZfKG0gs=A@d0HfrTbwPi!PrFaHJEg6&^H0cQtf6f(Z^6bZCBMGRy+MRiKy;Oqj+9& zniEQMceRA?Qq5>pC(RWM>0VcN=Gi9kI(hkBx^(f4_RkfaG!4D5XYi_pcTLPS+o=JT zBaE8YuXlzOef_1rU45bILKpG!)+je)qI*WZ^WV@h++FKJ-Rgt3`=5mdq6GcQj|h^Qq; zO8#`ygnuw&Vn#03Yc(X9r0e~k&&Npi3$Td-E_?eCY302rdUtaTiN7y-C|pF0t<0JJ z7tNk@CC_lNwDPA>A`uUlPq9*KeMbqYvTY#wFbs8{PB6;dulEYrcJP$&1LdJrkEgLf zTJaq-<09h6BzSXVpB6Ibu9w`wFAMSzg%ZAr7UCUPJFcwl#QOBt+$~3<1){^@EX+d? zM&=>0DnZkcAv{FWM#pNrY15U8k6#u8jH_*Zx1aQvW1-tgiZ&X%EqTSMpmJzJ{akK>KWLl;sEuc%J>_F(rsf&}@p86e ztrpHaQXn4Gf0V%mzdmOU^cCf#zW>XK)A{Edo|5ZBoh3`UBIyzy^o%$tx6^@Q)&gX- zMgD#LMVUD{E~8rqU4-^!?JG=9XPJ#^x;jjZ0*f?mBSr&I3w)&g5H35xf+158&QSL5 z6MAJKs}xon>z;eAIA~gHtsTW*Po=@nzTp_{{%T^wcfP^&6!C~bz`Yj zGrxT0Pynu0ik@}E-ZQpioBd!mrpPzR6?8jrpiQ4~>%Bl*gx>7`p69NSO}s*tt>nck z6h7O4T?@>9_PlwX9zX&qFJ8zH*#>tUGHbyYPNDU|Dci1?iR%!Vw`xo6EfP^h()5jw?mUVr_v~;0y7D5neLG$>P$ArNa z%no7SK+scnAo-Qzr{cXlz*i7Sop$m4MILBPO$t{H^By`%L??Q=-%8z)7ZZogHbjE? z1Er7f#}W2D3HITkELD^a=NdTM5sNohli$BzduZ6O0og*015sCzATMC_NTO#%fD!{3 z62^8_cC(kq0U@dYya$KT6c0kd!aTxI~K;3-vhDqj@-UZ+@Z|xT3cE}yL z^cJ;F6T#3=Xc~_S5~rC`G!mC08c)Sp>yG8%e>?4m>8>vS?b~y|P5%~Cl1*MVA4a&H z>{H8^-AGEdidyUc%Bd%%OUuWnq6a%Tcd}D%$fCaV=+VYuzT*fZz_D+6ueHC(HQ}5R z$34wBmglg>v_&SSZK8yXta!hSE#obrp4*j&-Hi;&LK#2lu#ladH&5D_sO;UVmU z=Zz7GI6HU7rj{74T}!5Bc>6_H45O#}kELW3nT@R0c*W0{{KpgO|EaWeFma(A)g*Dw z#x0zh7Rnv$I^IY}YbqsI!qoEuQ5n$3y^w>+opzx&5m1>8d-(ufyp_9+uX|)f9Pi;A zK8`g73{aYYlQp@T#!t)(;EWczvGffND_02VL&J5wQN^S1{SPH;If3Z$K`@n5p^m? z16F72Z`iIr=eWY;&ipkEbW zCYbz_eO5DViV|5Eqs*Mi(0IfoT1I6&>)Ov?a71{pM`69ZX&mQ*{)@$6>NG6vOAs^} zqkv;ljzsw7IrH%8&Ym}HxFEfhQsqU4sFQ7^9nhlXxZND^FhcQ*5(rmyci$sN{+)G5)=TLjTrgW?p8=cwu@|*dtV-Ndq02w^#^ZN)J;@XwOGlaJbI6{iAftc z4iW~EnM=YQJK(m(z|2V^XnlK02OeWw8dDE8r@wjnRGNnJA^qdm<9gcB53zu=o$vv- zm%ve!u-XXkRH!R!W;@w7H#msgDyoEG5|N8U4U)#Ae+_0z0wl@77prWBQnVI7`)mhT z)NNN)elom=Sf0ez9Zea%Of^OwoVS{?tcU+IiX#5Rj^6dR{3S7QqPR9lhH2Vp_> zp^}I?1M=PY_QqPV0oHXKAN04BJ} zq)h&0Zf54rNzB-#fiM&_GzZxZAAV#mL3d%NtZw#N1*!fdD5Tz)9)1AC&K+k8V@Vnw zBSm`8l@2pCH$O}o2>qN10Jvm7{WcPbPL_8TELv3JyJXb_Rn-F!WFkC?Y+(^Z%8tgr z9^9;f;%jFpGD})DagNZw9YUp0%s)A>`yR7mmJmN#OC^jF_*dgR*8j@-%X< zPm$>^L`6uRMY{>OS@g$+uN^9cQu zS*3ZoM?VDxwR@>*7ZzWQ-8sc!@^kLS%h#_T4L^1B_U#pBvOBMPz)S{SxiY)gpp{+q z3*Nt3!=;Ds`|~5)=RG|eZlO&oDlhL$w{!md`ALn_NBDA{_suHZNge&ndlE-C0-?Ty z++pHVLX=v}_%RL{aX>4KdqsmLLdKAMs_7q;3sUBI(btzyMfrp1BeP49O#P1 zKVdfV3JQ<1vwNd#u}o8845PTD`$g4k(Jf$KDUwH%YnDEh}b}_Tillj|*q_ z3r?IDZsG-UI|Q(Y8y2~t+;sgJKxUII3wSX`^BJh%?_^_Yn$rHg!u3=CK6>PO-D;Z$ zuJaC7Z}nzS@`==dUgkguTYpUe!EeW#t9qb56+x+$63x zd}LgvJ&zdz*YJ9H?7qIf9|KyOMu0Pf{!Wzn|HEV3$1Hf-Ixir&bkyk4k2vnyCm)~~ z8mz9aZ?~6UB@&?diR5>D_EiwTKvdNBF+Tp{s!NsE*|}3~;7n&Pl&-~e$jBU3QOA)h zKF0B-g|YE|)_|u}K6uC}&D3GO43c(7TShCea^Mg-ZMVNSwF=bEXNT?6r%$)9%D*7< z*wM);h3HiQ207LYr~BmlB_I2aHiI{`k)gAK+XmvA_93F1^5yr6RL>Eyza@J_nk^L@d}KLTo!!Nh;nX_*E>1XF3U$Q89kJU=PpEN_F2D3 z`*5$%+j~CIm$q;m@S}0=gpl}p&Z=K zQ?d=@vZ)hawXag}5{R zp&{U|aes=X#l&TL57*V6KVN#)l-G~YS->d(zO|h>GpR!w(Z^!u&s?pkAWi`N1n*o| zVZL7cT;-{>5gLd7mWk4xlO}8H6sws%)E&S>Se|awRQ7ycLU_^Fjhi+-9`KKqw&Sb~ zNvX5UuDP}v^*imIu)l4V`)wA|u!GwNsPxzWuff!M6S5+E^F;(Ot~P>9-C21UgxtGJ z5!`y?d>de2?E_QG=u^qTDtSem5=<4<-IvHv&Q z|0S*RM5grFoF$4uTmR^sMW#e(g%ZK39YrRTsn`}gX2dTdHtc$P|C6gJ!;d3eE5RTt z0-j$6%MGnd;S{p9vvZ{bChj$eV% z2@3xgbtx(LEs~Lzp2dgVWj$fgp#4(Y-OLxDaj7au9AjSlnR1lq(%xQW7?HuS?GAu! zCoF##(N;KL*ieM;WFI$Nu_9>sd@-K_+7XgdKX0Ko3NY4Ww#O$buCSPKqTKG}pIdDR zOwQ{gHF8Af1mNQNOM-bT(svyyb63gP2^!k7-DYWv(Hy`xr@rO4FFLNba-|zLHz#Dj zGh-M4PRA$|%gOfiEu7`u-9PebNXvY8y<;f?U@^I)uiZV0Zk9nHg?kCz61kcuW#Xxf zyRneB#uU95{Yx2^kH?rsSP(v|*QzOBv4%PQd!f?CJ`UddtET24G{OgmIsO`)ct-PAuGKMO1~hMU&aU~RXm&)jxKR#Am2kC= zQJ!cP^Qp=E9VY{o0Q?C9I()voT(EBa$cS9hsMb3%F6Jl6FmUhpKBQP7EK7BG@dC^Em*D{9&G(zp~UEi@|$As8fxtgD4 z81StEX%H@L@dEv{36pby z0y{SlJ~afYyVp^{Lakpv5PISuiZI&}MbBcM)DOP+b7(9b zjP=+Xqwy%0lDy7bUP{5h~>v7Z5+dnhD^fQW49592#e{Zv03yhTSe#S%F z4xrAyjlW!G)yRv3&UTK<{vP_(-P}3C`nqM|)-SvN;!AGP{o#O!r4~&r_l@PwdTWHE zAQFdg>dq}OBzS?e9(j0*oLg~mYhFJR&l_Qh?e~J|Li{j3k#hv`K>YYiqWvQMA92w2 zPKTqN*y+FrJ>Bv_Fkctx{*j2hTwoFb9ciYYlq{1-l5hp8hvM%gD&+U=1V_&XgK3hFhko*&7VJU>r^rR>NredOh(d-nA1vtbKI$qDg+zkdCH*g6xiobxsAKUuS+vXyMbSSCwC zBC?dFLDsUAEe%pCQ6#dq*s_elj0nk6RF?LV6lIwtZL}vu$sPvre(st%=e+Or&gDAS zoUuL6|NmR=`+I+v;LFXLrfM>L)M~lD_ri*&PjxVRW2kC>xPXt?e{^WrYUYPDG2{v< zXNEAn1M(a4@adB$$_vOaSw7eqp~u0pg&PO_@#=z9B+AP>YT61Fn?o@66-_0b^@@)P z6jp-qN;jMya2Pw2e@xa_*RrYPAOa99DseGv7*v#iH$% zG8wqmL}hG+rY-YkysjJM-9-4BfmE@FL$}PVtZi%>>7%&mPEfds7b-&!3G5OBV@hLj zvKP}b%sJX~1e0ph7dX%L;u){O0XU%voJ8d^WM~)Lmb^QyoSuh|9ZPqsq!+T!ei_2N zHz$ZIGAP~7aCRB96LxLv#RA+^h4!22j;@VBrN<^t+|oDoZZ-Iq3$TR~2t>zin!QQD zNN9%f>z82fFz<&{zOkz(s0kF?W$nQA(ApGk1~-2G;VKi!PjxViTBlBbSx%aA-O@xk zv&)~8n^2A;caZQwl|2NA-<&^qdGFqb(JjW#YeluQE}`c*Y7r0$`)#ZE-{;iaQdt5> z8T_UGt}RA>m_y*qq(sh__Tjq*%_9yHqUJG|8BUSti zOk>Mwjc|7%Du736h z0O=&=Va43gkpRYhLWC#$vW7DS9jyZnEn`=@q0CmskNt zNZs+{WiDZ)tFIHJ!}kfa|AyU%1n|<8mto5xySU594YyR-pB&Vqi;ne#sw9A5%nQQs zbn?;s+%U+?Q{%XT0)Nn;&o6GPV&|2|tIE(WcGrjyBd)-MDfw1y9(lQrrELI?n&)nA z3BG#n@-=K+Kdd4}aa`o&kQR9}9Ft|k=~PdJtHEY(WD_mVGL`tb@zhz+3HS1}qZ6-8ek!!2@D@9+Yli#xzc6@)Ah`etu#%7?@aVrtdI(?r{L2j0%Y2<*hRn{=lK(e117T*JN;# zrYY_8_{iJbo+q)JI`#LvZ61|dR{>YMR-bJ+J@K$(??e+b-yHR8&PFQNXzW&6s^O=u zJ#yrN0hljH8ki`d#896_$jD4Bun#>u#)(h^$efH2Sy9gQjuz+33S2 zlg4&@zItpv>{OU39Betcy?f+u7f`JNx%4imyg{kBl@NV0We6&;#v* zzWqg!uzK&eiW#**0l;}fG#B;h*DvSGFX4>5?r3QqH1BY}60qaktY#0wrvE!wYIH8X zzx$_G^T*sr)xAFOz8`dQI?2XTnEe=k+z`5+mSlT%%C#~-TB&8*lAh(a$aQazlQCv! zpU503aFKMC{J}9DGcAlCnD;vZV1og;R1CVh_HXuYx^nXJ`ArSuj93hTS`Dg3MN`~g zc|9M8fhhqaaJ^SPDhi|x24rq94wXQvix&qV1d4uCqaAdWb6%PxHVr9x*>A5w2Cc&m z&bF%kS~T7D#(-8jj+PU?B}RID?njG&mJ5c^V;nnEb;->rs4zffN@nIIgI(j5 zmp6smj)|fuM#TA6LvKObMjFEITJv(wVLEnV)?2ot=s|B=sI`G`HrCJzJ#Eef?TbIj(V&CiYLYB!l8DH_Wat(cV3$ z6dZxW-d{N_yvO7m+tv4$@Tq<>b-A;;T0T$L3oY3DVP#nVeKh z2;201_Vno|->s|N2-k&I*xD8s;U`OvkZs2S_M%%?9jl<0Z`Dk+gyiHp8Jx0b&*od5Kr<;h)cvYxE_mjR z8(&XO4jgyK4VD6Ygl+4Kiv5Q=_W9l5w;a`*Ji8qY=GAn?ZAq)$3itfER#vOZl6>s5 zu3Wj&#ykJ7zy5muBld@$p`pgvDaXXxTZZjSjh+6WhNsE9k<&bnO5|Yr&uvVs77(A) zTkWiFZ;I8^nIm}Zi=3Uqr%wy(m$&lKZ}f066L$;mfohd!&?P;<`M-~Fmv;%QITvnC zp^I#)t{TXZ@fV5KMi_%7_8(Rt&T$e+VlwR(Q(41--X_y!@V1I;TkTN{K0 zd!%bRtO|AU3w4>&^MFA})QI5xk6Ky5%`d!lc)wmt@0|LBVt#{!c~EY}^>40IeGiex z8~lDCQ+VxLN;_L&;&dmCn<~?t^Ly(FYe0USgbPBRx~^W`ur64H#>mt+q$uPnv-NQt z+uCaA_nKT^fX)G|w4&BvIsuZN*iZPXa~`1#K_Ff?>7i(FxhWui

    *->5&z4yh9A{-?7keXLVq%=N}a zaMkzFhGx3+8+c6APjqaq(-xoPHvs{*ClFX3aFB{_|Ng0xj{V=7v~^2WD*hv8ow>1U zyG}G4Zo%LX7yulEm9CYMN2Lb}LIs6Wg4IeD|JM?-fHuE}uS%z(;$E2qOQz#|^IwH((@6Gp;2N9)*xHGJlX z#XsLpzGCJy1gUuR{;V9=PZoGzq8Huyqh=tSxd{Lg7QE(0F;A29n z+g8VI096nhMjI@MtHt2<`4S}gU64(UB_FMQVa>=@guf%jpje^@hn{~8l?7(ikQKS-E@fYoEy%_64_BzY#$TQU}*VOm6mRnxB*hS7y&!1Ed0+}jqd4P^8MTUshD7Q;BQhW zsH=p+M^is`^ytmGEq;O9brR~R5ZB%5U}NPvT3!8D3p&M(eO+c# zW1{H}1Gx(Z1aQVN9qyqVSM&1G0jn+i%IqSq@C)r;G2`9(Or7RHAILmxRt){`G{--@ z)D)Yc@Iqo4KPFbli4_jK4u<5&Rk4Ovx#z&Q_>7jPW8?x#5_f#EE}^74XkfGEKlOnD zW>Ro7B=UHC9~c?7B!6*K@WDyT zmpscg&k8GU-=}kuS8ErgUspFAW6^&9xL?)(u<^-wt(v%cKjzZlTT1AH%`nV{+2=gef$qjr%lxO3S802nXBft^S9N|7dXrgBWJa*nW z*v7=;ApL(Gkq{9qLCZ{aFD|*;p6kWDWd8pyg>=|M6u)}U;f;7vo%lro20m+CM8zpK zyS@wBn3%nuNq8}hRoK8nhB&c~AZS8}(eOcx7`Xltd;pr&$BoNfy`PBNN=WURL+C`x zQK$OO>FYCE`}skeP9|~Zi`}mpbl8X&poF!Fqe$C!?c@Z+w_phCvATSRY~ZOfD1ERxjhZQq^KhdET1t#dP-tDS9I(oLBAJOOagIed5c%cI~z z?&wY5-suy*(o@^ZHOyD{+bmpWgc}Eu6|#tUalAqD%vk^A`LCch9`9kx+roV%&UN$t z{p!NV7wU1LUZa2S1WwHl)%4AP4UZcaQ2-d^gE#989r}mHn$<2YCqKmji%7E1SOV39 zX8g<#$_V#@+S*#3{bt(x%?3~kV;i<+bIZ2iC*; z7QH@53dkJaK7|L{`*Us+*4F%4S`nwkolv<^1Ib%E7apFscI^>~G=Nd~jj<;%#*6HQ zLH(xlT`APYXseZCW8qQV;)NFSQ0cIRLpdN-IBp~UesaLdcboQq@4TQZLO$R(NJgV1 zyV~|de^0Sq1tDBfDLv!%p zYwed;ClV7S%c9>MEBwr|rMb{fpsL;sUqF$gwzd!qj zM+7sF$JD<~6%w6+7ft5sy;^`%WiaRzGHI5OlrPo$+CyM)e|`0nJeuVz)^kL@Wlfy~ z3Y%XXF3JmhbrlLoNf1&(?tUHpp_ioFkZb}^(@#z3^a&%+Y#+atv1gx24#9O^~F@< z9$p_1an5D3ZTHCq_*x(OhD?=N2BRVRte@N?1OgMv6(NPNIg|POblTd74r{CsngM|{ zF-vmF(HW27c1rc|MC>$@3O8m+&BowOc4y*0L=U<_Y~4TVn=YOoru$X%_HKZhC@BEK zXfIz^_K&ij8e43YGR?CLVbpcR#L76n$ixYj{E4Zak^ATMPlNpx^OW7c*8h$F7uA(( z`}qE)nF3i>=;g;8g`v)Q_LxEv_Wq0H;Ml|tP=>pYiDpy|a<^bOI!{KvZ?-xy_kF(Rbq!3s7ju9>Sm)y) zA*=ShIh=2ThKrx0wTRY&XGdi{AI}im;}w_5aur3WijvL^4UF z7}Mj*(g3$(=g##OHjRY*Mb4_OqUv?4g%e#+r1!uDKMD{@A7%5J9O{%4cidbo`xHQ8-t7#A za&?9)Q;t2DV5p?v-u4)7n0cJJT^Ry`8_d3iKKIwrVQpa4GNCw~7!RrZ->2oFoT@1` zZ;QD3q&%s18FAmP3Qb*$IAn9v47&12CCdvtY-qDe;FMHOD=o{o9RI=XE?7l2rzok| zx)MGi46B^ApPK0y-{+vW&c2tCv3K^PbkKqW>vP>?`0KP0uP*aho(>l%%B=E+4;>m2 zzwnsoffAOW4S0Y`Kc*37hA4$;ryj%PSxC<8Rf*B}SXS z>?*e1Yuto!!+=yU0>X9_bP}+TWab0Vf0GX&Ntf?@{y2F1*BC5G>6go%Jn>3ON?NKH zz&$I!5Rw>Z>(f;OQW4HI;NQb)S+$q&mO+}Z+4>Vk1ZDdtbWyrL&1oQi6x6Bo0PBtf z`S61o#eme6*EKF&tEJ0J4bwEj8M<%?^3fMCVD_>CkunqqR4i{q$Hj-mmMZ z!~&n#{7JzUkGX^^4*ht$cavQNW5??N?$(`o<3{M(%oh7--TMv zX;xNM)dIGH-@MTiVu9H?9i_9llFq>)WD4rG=;3Qg6AlxC0*`LXj9^^pTT|-bZceUJ z$*nTg!BfY!+{nV6$La4+CQjCBK0u6Smd)qU@XWKG)(VPShbVY>cx z|Ng${qFcANI~K<5M@#FsIso@eZyz7~PHhzL-@dgG3%LANc*hoqe}O~9LbNb~KMtKh zMosRyw;Q>Y26>4g zAv-^9VB0xVSMZWDB8Q#}|~ z9G5+{{L}>)YbEpL{%i5`!HHOj|Ajc|7A_q(XrA4#?S<^|hz<8>ZHZ?ZE={LiziMp~ zcS#K0nl)-5+F(gE_(*?Zm)lT1QcJ#7u2bG` zb|Z4?lqt`03-a?XqoaENkp}r!azcht|5|-rMef5hoU~mMdrUgC^1bLh&Udw)JGVph zCKlwng0bDy8zw=fGWbYky_ha9`}tnl{DLdX_TC#Yc9OWCr6JSlLW{5Yx)b$kUlM?A zNBucDHSz1K;o=VCw{h6ep%+CQpBD~w&#v~Gxp6o%g-3Ao(?hRZx|Dfq1vJ=I9ZtRq z={3(e)EgwR$!5^1y%?uGj~{iF*15r_l*M*-x0qqz1S2Z(+q;%PhQE-Q7+_4HW**f- zRkdQi7l5mIRMRBbkZF;#Rk6Y*SMCnIO^j!D%1m=}XkJVhfirL1C zK62AWy;%Q&Dk=KhRN4K`qvn@I14J0C@5?A}7F2eYdR*L*=xQ2JEzb+#;T2ca!ZAES z#SF&jKY00!0~KV7FJ)6b-jh?0Ro59wHlVe2)r#S`BJnTfR6vjv z(!>%D?!9;PH7X8)g_+ScP>^-J8^@c`ecNL_)pu@k$WT?jo%P%(N47f3C2F<)G&;nI*BBeMVRgnUHz;jV?QN@boU^|4Y5$}`3YT* zfuS=4VTnpamkaDABz`4@pnIaMq#vOdD3jno6j4eFET{V!9zB0Y+%5wGTAi@@BYkc0 zx~2*d%V`f8a>&7uQwuf{^QzV%RWOblNDqP3@AQ=nA&xX_HilgYcdP|m$wMQ|gZASy zWJ6zvJ8oZw0s|16d#>H_pZd_tbt_^SV6>GfhkE|>Qz>NaMZ4eTbI}XasbidY3~L&> z_Ez!a$O^I+(g1Lpq}C5e#hvn|%3dvoyzmeCBNhRO$=s5|k8V%9{jRcS&(6Gl)yCw* zOPgB%L;9(Ax13X5_vPO3*QGQPh40A9rC1r?uE*$qxd2H;@y3OgY*KS=!+MX-h%8oXGzDtGkhtemuPd(b9o&G zExkxWqm%!aeF2JVM#qLsJpJ43b{VMF(r>>@Jy_CZ-4pemhvi)4<^{vO=ScEatLWol zcf{1{N$cXu6#s#_)4p3q%DJ7ltfr!^LWmg7*Tk^5Aj&SYTk0Isn?t!hoNDDrE;#FA zGS9%mr2LLEBmdJ=53M-?YT9Hohs30k`Twc0k-SmXU4c$0Zz~E*LUG7|a$_)(3?I8& zRGZ=_@ero?Tzh-n*T&O01A}@|Xxd;2^s?l~cS8uoF{!Vwl4m1kMOVa5q&(m!_@};= zZfD}-HvB#CbYjbNF>e8yO#!k8k%De_U$7}=zSEQ!@mFnlz<_|oPtH+(NSu} zaLW`%eQo}}C|t?ep)KspBJJO!^0q-5pWw!=G|zGnb)6*S)-Mm;8056A;6&A-L0d*| zCNQpeBoKu}BHatwh|S_-%Wqns6G%dD^%J*w1^I`H0jWuv@Bumtlr4f>a!lsLujywo zYJ!3S@kV;rQ5%o?{{TR-;SKZ~#hf2%$BEpH2H5V2h2i;~(Y(`ElMb;z6!`rs6!m@V z!Gbj$o_-aPG^=~I==-p>y6Neu5*2-&4Ss3W(}@cLF$8P`-%p_xkcA4zNic`lzrpF? zD<8KOYea=M>T}k);{LwAv%rlkWN5+ATd|qNUbgVZ7maB1-fbWA zcRZH*wo&Z7;#aGk9$ognYeY3*3#F|vs`KzQC#dulF&plp!8&*6p`moTw>C8=;En2l256To7g{>eb%lB;(-3xQ* zO%%#koxXi{4@U<(1m>{>-OKBvHDC;+w(BN|i&{Um-jVzMod1Y*ms8`o_7)L>q)58D zy@85z0}0ENsoH_G1e96|PJ-1o+S0ltg6VC)xp)Kayyjh0?KCUjiyQVKPPPkgyFHl2 z$InvkCXvC!9*?E4+w8Njcih(9x~wd?GovxAJy6Z1clVexzC-giJ2I9L1XM>&c_r$K zSI6mfN8@tRP+{1qk76DcS)Y=F19eX|Q?Qw|3K}+O5ObpI|C~{(Z9oEWVN$U^f&(Rr z51Hsh$QTRaaO}xREdSV!GpMs}rJMlml8?Z+6$XGrnSx2t|A`F6$ViJrYfhwnJ19r0 zm*%wGF?K7H{fGJamGNIG1iiEdSg}9y+e*u z%}ut|oK8+%ILX8PTpLDd3BDB3Ss+ZO)@j%~~m(N)pqD?~R&h%bn`*(Oqgs{vK7KuygNXQ5OAd!5btXa?fJned*Er;DD|QvG8NxB58K7il}|L|6?q4CWW0>?>eK5x-(?^MrIf9wmPu~q1ffx zRa92)6pp=3G(6U@BMoImDE`~yQ$9|BVgWXQcqnu)G;Jvde4WDpgVN< z@T!w((*0!Ms=FPS3|M=czE4EN;Cf7kVN{cP8g&|akQNl0GEV8XU%PML3*&C;^TOgk zV5G3&^w8esaQjrJp+Q$ zvN9!n_s|eKgl13h=$}FjU(Oy#g9Y`L-isjZi6x$ump0<4?^KKwsL$z#Gaw)qZa~eH zJA~Gta0AVA>^j;)nH0jF9BJ6C7P7RMab3sC#M*DeNHXI7X=P1J%%aaY+?uIaxn|9HE+R#B zY(vMcsmm{*e%!6^_hWkYCri&cY3b>H*2fPYK0Ez|`RtD;uSEP*9{7D|{_u(OCtVg2 z7dt+cqo&!3lSA)=vk?}X5;=^6EdI-wxUMODOv#dz7z>$`l>y%0Uwho+LaJ#%)JK)J zH5xv2(%cGfQu~AvLdduQ!JD=Et{(=?r{p3OI>hjKNmhO{B2{e4n{A zMPLZU=ah{@MmobbX5f7$Qv<6;s0W;84HXc{)>VWs<3^_+F`^B{O;d62UNCA;*HL1o z5L#Uz(Dit8-bqo~ zxLwx~?kDmrhA9D9%5b(J|6OF!|GYP&0G1A)S?~E8>}ra8cNm?rZxA&5gq==ssS<3K z$uE8IH}pJd1I4U*xBjn7mbj#xO1*Id@l<1wOTe%0&|dYI+-b{s$f?Nm=!M*Q$-x&c zJbBtn%eRD^RE9Vwbe4&ge({{{zP+?_AJEs)rYoz&nh|VK-Z;2Bsw-8XZ-v$!r;r~r2>Y9I#n$#bVvIE9!4{q~!xxJ+_ z{#_NPXY7D(Y{O9`u2ciqs(32YMTd$>70eVSZp|8Okvjcz-nH-E*wi+mP#X&_BKBU; zYs)d#*oF|UG2SL#YQ}Ap8!?DW!YN`aZEI)7E|`alBR(9kl|V0LV!MIgc%!vz*SdRn zEap*)6k+W`0;@iZ(>=Iq*jA;6O|-!yqHC$YpFG3VbrO7>J=Rm;y@Lnj1iptD;CFXD zqg}+{{qMI!7vNnewm&Xk{|Q1_w0lgj#bQSBT3yvDSD-H43Lk5;&xryi+OduyX(tB~ z%O2*qUL3sUwSrQjC5U!(HOQ9_^KiZ2*M9xzh!xFd>nYri&_Uh0l;Hm0@BEAVepgi= z#Q+{JN2sRI+pro!_&d71AnE}p%aNB(57akuXj>@z@2OZ*B_SyQ;1y>j2TvoOv7zf;Cti`t22z70uyvhe9uRG zHgf*S@9raUPG!)Xf;0qz?RCglZX?eS6I+Jy-RR}Ze`aQn6X4BBcZMLu@y5~UO)gmk z_TO4h?|_cgx6zRD@^aR>%B4BG`5JE;Y~hmFc;)Nfj)tu$krbPyY54x_Z@d7LXl)(^ zzRzGy@<_{T2hM1$nuFZD{Mg#!>(a0(B*O?Vg(i4|p!(7_Ha_;L!BNZ;c#{$5RD+%} zU66=S2_jKeR!$QRJ!+U z(zI!JeSLN4W%4M%qo4-g>(k_PI@1gFu3c3X`^w1FNSqj;W4MA5;dV1zyWZ`-~asoE(F*046XW-OjXNUUIB8^cktlf@q)Ma zoa%t_#!GOqUf4IcVXo4)kDgwh%v`yi8neFUpj2MZ!+%6K^2ccH(po=^F7D9rKcvWy zS-*&u{iN}y@56V^>t9iu(YkZz(8&4V)g4E;ue|c<)wpiz(HY$9)~+)1HR&FG;MlRE z!1s|oG{mN+x&$U|@sRl){J=7vm6vDzx=_-!XMGyC1ZS~+9$_B^57!$xGSU3c1KeiM zo<2PtSp?wV9{XqNBTX!)X@jFPmb#`@gnRz_6?6XL-0g`m;SZPF#nfN+E%$~|Emks8didy(QmN`)Bkr8gult^% zU+c~VD6@LRhsY{Vy|?-=!*Sgo$RkQo&$wewtH1i$WSkfl(U-bE-qGu#O-d7?;WL$( z0IPEVKP&eDHN*r=?x7_K>R*S{qO}p8*lS-I$?faE2p<|TmY^>cpol5ZN|@p!2=Ed8 zATwt14}>Gslwlqz5}ihVE^RoE{%PXr86_B`eHgguN3G$jl54682IbfJaFJ0}3@0E7 zyy45*uOP*+haoyjJEsMnAEH2M7hw{UP)n`!R#brC7Fs#aKvwo2IkJ;U-r%w6=Zc z&Sds%hV>};R~(Q`ZtXf%2)^>H4x?8G;eb8EQU*{Oo^%33=m%2V%)MXoF*{~wP_s((c~7v>aGujQia(0<(1Yyx0IU6_F@KY+E}6T59Wn}O*udB&<=H-uxAZ71ha`$77EE^ z-%|ZlRDDhAp@SPYZ!(eJQ}BxYf;5F9nIEW@r|!K9t>#eWrUw1qw!1nPNK0a6aeHZ}E`4E1N5)qL2_p^?Q zB*teK?J@(~AHUXJjAl6rOtIZ!T8{x@gF%C?tm(WOKGVFn=P>pw$0H||t_UWbfS5awBtnW6RPBUDWxpC(<689A!$B{!%jF;>w~Bwf7>BNW2@z;T%DYyoaL%l*IX`mPJFQsEnOpyl`zoasH%bpH=KM@2v)R6>Oe^2g8$XOfoxCU~NOg zGyCI}g7fFkZ<`V9MFharEvLpC|C;+dko#jE!iub6!UnM1>(C5lHS<9!q7@%B>KyF_ zY_k^QO11_=$k4lAO+Oa>v9f=Asc{1(!Su*DjXb-{2$q9fV2J%3-^!4Kjtv~R zqhi|U&{M8?RiVa5T3!p5G%@h-WJ*nRZTjwS7Ht6Ya{uz;EXyQ5@OY4K9K#i=i@nTB zLJN#Xj39hv78>=d=4n{pRJU4uj~W(~Vnv>QejQBC!;c<;p{m%k(R^0FOWgM(oUk>} zzci}UhNovV)6>%v7GLWfWB-?n{9-Vb3Vu$djf=1`nPzQ$*P&P2=8$vlGDhWsgn5%W zGoud6`V6>*=t}$GM4f{ZUEnOzIQJb5Ofb+NC(9L zvUkJ+S%#AldwNY)zW*jwW^7_tz^x2!C5=OIaWVJWy!eqyAr`vKgC17a4sp!);!F^U zI!66^r4#?n&{f7C)Hdx-w!U7P=u z_O6Wp*NYQwdlzym3PA~6%rA=h0RV%j`M1?M7Z^`Ofr56IXM{_+A0(#L1uQ^u>k88q z-$TE5GKBIbcwlhqQL!pvG$2i+M2Q+2HdXBIVyp#|%`V5KD=bZ9fgyw9 zcEfp-)We*w5(g+X7WlY!Crb58_yGtddM69iTtq=ktj%mVv&>69)fM!vmaAn zP#Ps1@EUxY%MdwAKPTsBKINtQ3ptr!W9*bhm}6Uk0aR0&Mv03wZQ+TEF8}Se zBTA$sY*$Az!^0)hiTZ`piAoB#>4*Ea^3e9(gQc(!zw>|it}!dOtbJdSlXI{|GGwU- zB_>|3`-?SGGovXpA&EuAT%}inqIb5v&+Uwi36RHk6%;&tC_6vv%lnI!etFjZ$=MI z;on%S|5NK`Teoh_ALZHd$-i6xgTQt=W25~zq$(~WH9=1jQfgS8X;1(Ki_*0vk*xkR@9T0Jxe2(%6GZ%1t{CLQ z;aaU@n3D(A_F#SeFS5t5;a>v&x%21CqabMt*MoD7<9-{Hk1p#cnZ16{F=eQi>+Gv< zJ*xJ-@!yFTmbg`;LDs<sh*@^5C-p$*7x#M^5gh<8@9(0vhf!uNDp)KD->9 zF_qI+AKk9;r{DfPg>{0~q4i|=%_+9cRmbH9I;3~qKr@lZ<$tRT1r9KXT?OS!D% zgYM`RkVNe&)m(?Oy}U*QQNnG(fUF$PP%$n3lwVHW!eiIQ^;Wn+*c$pkdhy23{54$7`R{X8k7Eb+JT`9RL!YKff~#8Yi~@QD>+4uqXzI9G(d~ z^v_%h3$E$+sHxrOw8_2Ou3Fe}YFuvgnyxeqCNK$XIRhhPvvcAWc~MTN4)WmV?xdwy!_G1(n(|;M5yyY!Fv_XvBnzg9DPkrmPW07nCaut91H28|=izAoLU+u`j3^{h)m{fQj#j9q2`^MD# zeFK+#lT~rKKnlrN6LFovaSANUR{nbw7XY&*K=KboolQI9o#9>9r3p~8m8nZyuEByISbO)}c7zW_Z8x5c!Jxe$ED@hZ90u}l z=jVSp`L_Vb>taO7)Tk(;_MV%I%XKzI>_w4_BFFycCR2ORo~Mz<80!+yAF>mMk@i5#ko?33IJGWqZ=v&CPn87ZcuNs z_viT)gD|qC8(n$8?59ARmd#!)f$Hu;hblT29uVNjeP!)w!FGJw&lI@WqBcV7jUrv* zNezSbNcY>@;v#dwrWR9H)98fswu-Zg1Bky zb69R*niD7S9oIG;kAKEK{l`2hJf~Kzxi>ffqb%Tpe@yjcgzi>+=g!WNA0(Z|`e!}8 z39zyCUakRP_FKaOd$*v;-IwmKbeZY$)oL6pAxOrOewixE)kRoOJ90^!H5|!s*$0|ZTjtV`Cd82 zlteZm!*q0*yNGXOn2jO*pH7?A9+>hQ(IvE_W3SMSpMP!R{8Pu^WkR|UpArn`l^ADw zJnu)%vL~qdmEfj%uIV)Hrx+FGR4|itipu{zOxKb#>w{sBb-nq-{m(sGz)DLPFb}uG z)XPyXK;tn2t2ktRhxyvF0aL8)_9U<3I~dJi;ZasoE77_P7VUdCG=&<7wO5}i`K9ho zS5=pZuCFgAYp31%GXEI^Bs4Uvx7cb+A4a21jm^wg9QFmSfmVCfsolnzXSKd=pkP#J z>9(eVf*BFe;s(h0V@P7jkZ5mK=aKt|E=>~QDNzMj0G;UZq*>+_-h0rQGu>!SX)F<- zT^A+M;k)akTZ(nV{Xhz8V~@eu+?JM?n;!S-$z>SEflO|MumjF8fc1Myp)#v;UQ&{R zbz-!we+YI?>-#4ywYQ&W*sj?N6F66e29K;5c4=(Rn)Tw++YKb=a4d2fFVw*$Rq1qSXR>t`J-N(X`*us?-v>}kO6c^TuoL5s<09u zunMLo)*2KFTqde?6fqF`46BRcHAb5TKQBx175Im-CSFooG1BJxh@5--jll zs^yj7XV48OnU5GRn3S?2WF0VwvUhTS_aHAdPd3G7=04oB)(JRYI9^eTO|^+7Gyd47 z!yz!726xzllo9>IARvVNuNUdoTumwAAmed+GDhWw3_k{11;L&Amibj&hx$iob(3mA zhChIVN(xj7^VGzVj@nH;zZe%TV))GoXWF;DX}A6N&1A{m`k_7`^^e5inbQ%mB0JNF znr@C_JJ+sH+vd{BqEEYyF!yWaix)e<%w`;Hc_awItRfyt7;*6|_GikG|d4=jWfd&=YVM000JZ#XmUZ_N?Yc zom*(Vb{FKtFG>c?Cm8XJ^1OJc?lN`NMJ2{2mch>W@!c3BMHi){Y-^Eheq?a7f7;~g zvv-z#2>je!r)U;;sfXof^TTk4@oV$b*d7lwMx_}Mg+ol))|HhfW5CL>1&P?Te(Lt` z=eDXbkb!DN2XI zA5>nrU}$+{v2*)jUUVDyWj$9 z`m(ymfEnwgyy_n(r&(r< z=XB%oEVYXeOubGny&E>a>yx@`j>|L!GV?$F&uAB^DN2hpgro*>#K(v7ZVKpX(7LPo zyG_m3=5!2?_8s!=%&rjKiRGi`jUV5HCvfDO>os;abiMGJ1GORcy)B#$xt?aj;8F!} zrvU%7GIfee4$wusJg?o@n&9}7-_Ij?rm)u7K8ZaBusD7=G$6Pv3%rMR?RwmIpxT6! zApu(wr#7-vuH|lBrDRxh!g|S))AwrG4lx7#qxM~LY9T!w4?Ul5vD@( zwffXfxsgPD=&7Ckl7DT}COOJB4i4%^9FAGq^4m2Qgn8}K(1XQh=u~*$j?BGXkk|Ux z5uyliJFdI9ZXfOI5{`iqS~o8XU2jzV%(;Y1x|j%-dXx@nn-AwNEzb5c|7p5AdY4#@ z>3P6Kshi_WN{TC^Izf>@jxGlz9Ge9-Id|@a?CR3)#SR8lQfi^=C4uZsVn_x$>B@xQ zGmB|2Ru4S`>-Q8g$E(lGOGTqUx)7m`LH?gdj+ltNx6b4nVx;QTS4M3^Dmy&?`r*x@ z-6FQ;)_QEY3U9OfR+mg}GQsM2d49V;{&B#XylElaA;Xgvx+3_-oy%_kQ>mzX*UIqR zgN=2)-aQ-w9Z!A!x87zm>mS+%V+y=(1_lQ;T;n}zLQ>bSg61VSu%%l^BUiidb$hqf zH{kQ>|1pZG6X4hN{{;mFBE4UHNs}LNh&*2Q(^2_vQ`B~2)o63?a?As#ft&w1IXBQ& zJbJDVWu_w5r-VRMB*4SARMe#%i>DaC8%yi?Q9TU(fPz*6kN5PQK4Y1)vnrJnmPqz3 za|#NQ9UWbMeD|cxU2S?&()36qJ#`FEM!b&KZ5aw4d3EE!@jVaNz;7nK@CL|wzUPSM zmNhLucvc>x=MmdJ%9K?zt*nmRt2_$1bl&HaE=#o6um9Trm9f-oz<<7A!1j%f4;nbo z{doQ?!7g9CXtv+15lw78Ig4s)ME0htsy2kyycil%b^EWsT2kJ~Gb)N{D5_Ig_4li7 zKC7XBmuJ{-dc8WIP9bLEW#o=NW}Ug=sf|#0ycsfdAlxGss=uBFdPUpqz@x=;(@& z#v!v?SsZ_j#wNPUk%)MHMY+$U>6SaNY|OM<28;)OQoJvi%VvK2?O&yH@6x4}Vh&_< znRE{|GK%`!y?z~LU%{sfsH#OQzAGSCrVi&GA;P4V!FcnTcOfbhvy*G-CX^Wi*;(w2 zM}H}|M9rt|w2tH(m_zUQ&~uH(2|4vAxEXV2Gxur5_u?nG>gr3F4@H*sC%%Ulo-Xxw z-D9S*bznODu0{1=IyO7zpWO@fW5`1h8_nen zGuhfXKE}$r@pNdo_&Bd__Z!`YHn0Wha=rnd7LYL%RDLe37ZzSJQKm=UTqo-uS6A1X zg(HYo)6np(=VZgJdmjaH{`dbaA6``dUmLgwAOYf&v+8?b6I57gJAAYBOuVWT=KH7a z&~qUd^0H@Bn){VG;6nd%;r)h;pqc*dXpsUWAQ=g#j=}Cn#Imm4V}_Ucowu(Cl2`B8 z@%*J?dI#b|lb}~xx&6C06FD~_?h0~bo*y!v+tI$|B<|D}OmXV)1T*KGns_kFupeGn|?{>HOrg#|Kn3t+_S|??@?n9k6(7EX#MMQtLn`| z4^C`M8%P;r5tGgU;w=N=K!mh8AqU1-sx%CrS-bz(F+W74W?P)Z&j7mZijK^^N&S$y zB%rn!!BW$Hp4v%W{l#Pk5A9N zK#P@e9U^_M(>uAnWX)aP9D{K(t>j$W;klq?#VD}?Kv`mn4-f~S3&xJY zlY=di`8Hsu0)sP)8P%~@x4^S?-^7U4uiM>LYssSK!m(e$aT~T@Ck$JthnJVMAU$k; zb$O&?LHm*o?^WPJ^(pkJdq-JW-Mx~$TWDadpwl=3JJ3l_>;1kD41CNuQ))Ngem%Q& z3lVQV@qt%)>PfNjXb873LQxUp2zi0G+Bq_6GxCZ!N0W@r~m z?)lemg`A1t;WL)TRPLF{4d@DLz#no^Jt*0IE2}l;Fpg3oBdZ>Vz0?Fh)+MuAZ}rDs$+{(#;=YuhW?P z`jmT$=WNPX1jk6t$lbC1+${aie%sH1x@qg{Pw%e%>X%V31$dT}0~r~E7d-H2VrkGa zVM?SP*dTNL6xQ!b($A-lhL5bHFb3ZZ4+f`^Aj|d;2!RQaR_!V0!C4!c2#T((Q3ZnZ2o>|iBv(0 zp|S7)6nBbS@yNu*Po8U?XSv4j6Ho84p2Whu20*hIZP9~iWn67D*zf5B(2e8p(3~Cp z!BK~paTEywY}0%rxA2*A3(??h&d7}17t-Bnh76FIK+Hl5$hCtewvR( z@Sj@*7|D^|AJ3IV7{8G=Auf5s?xoP^#><&>sP7o+-22$l2+vbd!rk!NObZ7(n$m`tV7Z8$T*VED1QZoe_ui-fajXN|E#7y-R(`s`P~AWJi{I^ z(yD~~r2BDh4h;0p&#LMXq9tGZwn=L;W}zJ27__i%fl}OiX6PE?6>YiCo+a$l>tqfxqlM{t56DrWBGypnV^V z`5>=#LUp^D9-oFm4lUp!Nkf6(oF*QPVzV@8(9Aq@juelbayY6?c5Hg>;4qZS$Fe5{ z^=G|PV~-C> zKqcau$E5hNx5k1bU{Kd03#fte&jTgGFSs1)hy`$7MFmBb^Z4NG1!GucqB2KYx){&| zY(;7#$oFm_Pe=H6lc6A$(- zQI$X{e)nycp2h~f_FB}Lsi@`ixyBi2QWmJnV*Qz zMF_*?DMS!SS8#V9%H8K$^w*|PY$@pFMk{Z@86zbvtto$#SRuG&+2@F(%%&foHVHvo z%mV52b&QQW>m|Htz+cXIw!b43kex8lg&JQ|nParVjo1?#*Pg#ZGL^ruLympk=oTxaaPWO&S}ucQFINahwPd;NN0McSGC?p~WI z-Ql~p0A56NF0pr)R|S4~#a<&D>)@fk6GH!l*WQ`!*--IUfN@8f^jw!+=la7TS3rX| z7L@@_XgfbGgJgcwTcZDP!+jDQd5T7zl>}6IF4Bl*OoERXF9A$vTU~XNWKS$wloS$T z%qL9ZOlzg6XHV_v??2mt+sYT%-mgaZ>p&~L`W>#xLn&ecH)?Qh!#XX=ueV!^ZsY3u zPhs)nNA-~TK0}_nH?)!c z&+6*Njz5Z@D{<2FX5-pY1Rl&S9m1PH=r|`XVOi*FU(FLjzqEG3qm#5m3?6QB79mS}W09XpP>NJc z!jkJb`H#(OXry6h2`2>Oqj{?lImV%#V1X#Lq|Ot)2+V%kzup&-3u0w^9u)Fr$iAaC2S_OduERY~?{F~g8(PAZKcZ9{hIe8cmzYT2z1HgNJ-Mc63;((#8a zCOz5U&V~tbhxhH%PTzzuvy(HHKkcm#^a zofwsI!93<&-h|>%^=+6iY!yjdCl_%tx;VF7WXWxPqQ<|s*EmgYLxLC z=X+ILv-(Rj=P^oH)}KrXx%Q!|_U5UpL(AvtFK3vV278?&s=YD>AsN@awG^nov_|ow2^&M{*=m`zuI`QDF`d>d0`h!RF?^iGZzJ)wce8rE3=MdQ!rR|0$J=cYbp^F zr@IS9;Mx;|G~$WM^P(p8sVFlTG`YhKx%-GZdEGN|;$mWMoHqLgPZ{ zb22h#MUm*e|*Jc;Yf{82B9S$E!NkkmE z2nmm4AFm{+CL%k)m}~9YPt7+yJvSp*04?V2;%SVfo0v$F1QZ_b?7h$jWB5S$aXcRJ zRljp5ne&oo-E85)g)KV`otCR{_Vnp8#?o@RAt&9&nKZk@L+mOfeY(4jjuO99FvSB0 zW_l}SnkZ9gNoJ&)$qC$a5Wk%N00uow!U)9HgnwX(pQN9#`ZPV*LQ;}&C~n2U#2QP< z$*~+V`4n7UCQ(6YXD+81K?Ro4*TmB%G+!YGg|;wsQE4mKNv_ZDD@iY#7kI`?4QCHu zejoifbG14vvS-f%u~N=y9)qo%gl)WeQ)UVRc7hJjGHTrE89E5xIajyhk3rDXyy}k& z5;t_9Via3h3hqCbgl}2BYE`oA0Lm;m*7)PbG3x#P{`imV7cQX}F36yG`7o4U7y>4t zRK6cLt_8f|)+ju@&YrCpq_MjL;03T;0|g)K%g1WDs@t|}hZ(-bsUIYujlq}q_kR5- z0|^uI#yy)PE-JyFxXPnW;C^GCf*2nm@wf6SOIgPj*GI#DC}Z7y#gk89h$eKHY;+&1TOW3hcIhfXB} zLB`Pf!0(UN@8u4a0}UQDOb1DY3=MTWSTSvl>T=ErK+5xl^=N*Z5j{8xf!t40)<6tj7u(aFqe6xFR zg4}&m8aPL|^#?6B!t?hV@(Q~W-I7bT6N*M^TV?xJS+wCExbI#VX%64v!>b}|1gciQ zE?qk7{3~R|nbgxtqam=)g8Gp6_R;+;;Uqj-E%{x6yrZ~Wx|u_cs0T7;=c}@@&0)yN zNcGm2-ItfM86E?~TsER#?|bn0u+`&F(eF9^eg`16Yt@KNpUavC@1Y24&h0-p9$e)n zt8nngna%}xh634T55;VD8mczL3QTs)PZj3n&F*CEVKK`YNX9Pr!k-Flqy#rb39#T4 zMYkF==gX4M&U?&t?xDziQQG7%nE>wOM@kB?aMguZ$l$e7Hl=8Yl~r zSgNcumQg^&Mg|U-)AEap7bw*FSw*O!amzWk4C_j*PiF^0NpC|dlJ#&IB)bRSm;^<> zvOb7kv$BG~)`fDDYo$?2A1CKGEZ36?AR=HFT_&8swccrkn2Rw0KUkf0(zGc$w;uhR zA6^_2wU_a&e2q}6$Ol6MP><2uKCwMEDn}1Bhz4Usb;S+VPSuAwPrsJ#JhP@ce+NOg_Ib?L~>^Md^ zR@qr4Go(R95z(|WN-~p?oq0s1v?&#$MAj)sN<(F2L`p^^qWVAI;oN)wJ*<} z_xpW+pYeXb*1K3#^>%sSL& zmX@)i3CO#8xo-&fl(CBeVNXs=5mDuQ+t`25;>QQFc&0N#N4UAUnYC%$cCd`O)sA&Y z^VK*VE~rk*dNf$$mC{e!;YCfTpJ$qOYI<<=y1AC? zpvSHlFQ#^n$!*%AMOWAOV3oSYTH$P1zRcMaqo#4Q&GyVXLKliE+rp+&+OFtS3hK~@ zBd~boj$obEj|;M$ex*aW*}1^v3Mi}Io0~jC%VvJ!e1UR&&!f5L7x&>2&fonv4{_cLzpWkbtXSfc!^M1WMlMD=+Bg8Nn(Kz`VDQBV1e->R`tm!>*vd{2~$!;i{&fIcQ z4O%y3?U%E_@V{dl!ad}BcbCzl{6S@ZKY3!+i@Y{k9NX}7zO{=FRNk(={tI;_^Ly6f zWJ@2)(O{PsQtL``AT`ho^D3sdC+AKxc@nVh40Yg{w66_Y_dk{Vx&7cJqa4~q*STVH zIw7j#)1rq14*oe?(_!)0tC=?U(O}2`)j}@WfILPhdXmOu_6YDYqSU?fdg-|N`Sb?X zO^W5_=spjvYcgvfdVIAeO*#rivh@3xrCzD80N2)~x1C2k{`hgx4V`CNngpNbG=P0t zFkbg2jBRo<9pet#zzHc=DnGXoFLG7^kN$P!7+u|-y-(jV!kNP^XebvR#2CwH6S17P zJq`~=Wy;Z^MB^$aZgCUyjJ_tBjg1!`PNNo|3nG%f#G2Z!22T^g2sU67^YhrgxIi4j zL%F2A+lL|pFo``K$BXqN!6s)~7++X=E6ec9{EnwMHg(CnmH2uQIRi*~8I#H6Fd1b5 z*zCcE+lGoIw3BAo44PONn5cw5`N}wUtss=b=gpeu@7^`0AVAQX+`hAu?#r)V zz8F^=hE=sj%^mgaKA4fX9qi2NZ8-nfrNJM6{Gn*yFkBMk_=@!X6F8}7xLiIec0ZZj zK{L}#fu~YA=VJqfc!@cdbl<5aevq|$r_Tx|L|`( zLu0Z`j=Qckc=FK=>96_LvQMR@Qt*ijD95F2rRn(*kfe6%)Y=Fv2qf0d(ZQatDn2DX z+@Hn%fM&Z{yT&eeerwuQVo$g=Rb&<)`JM_^@&4pX&cz;l)Rea>V0_YCowDgvo2Iej zqXFI%{~-T(=F{p~HG4-dwLe$3fTm*k`3Yi3mcMuIV@I7RixUu_mw zgcEa`CYk7|r^WPt7bB~cw(UIe+n>V>8lk52o z`CdZbs(tq(kyh5glF#^O6nl(7>+Muc%Kh#BTPWm{J#P1E<6-1hc)s+AC*a}@O7Bw@ z7&2Gce)}L>vy^?g^P_1*&6|6T+`23 z&(m`-ao9KmXj%HZW%~MjCBWHG7OAGu$PP4^c5c?zes3Ni_ML7<)m->E{*tl8xK6Su zN(%AVym|cY(OAT9_KoICp-1Qy?hZye|4M=Z^Y(1sTYo;kP`EvODlHY7Z5w@=pfly= zAgBElXRU^>K8t<*(uL)(c73V}NH9-Wdog2W+1wkM1Fi%w9P{UiuTDH!KO$i@`?MK) z(XoPzmQy1l`QHbXjN{#d3)@@iS6ZI%_AZ)iuuv2C#bd_!I;vQKeY?lu*~CFQace^%Z^n@G1M9?SVI_Rm#?> z4_oONe*7a<%KOUlC;qfOHKJAH(%Vx|%w!HYy4`GmDY;PEBZP zcQN6UGV4Tu>Qgq{EZ;#%y$|v-ASz{;Osb6!0ncpm)AxiBh8T!AsPW+Ig2NJbpQTgtJX;RQL67r!qkh& z+J42u5Xao;2?w{_1IUH*Q>^D28x=5JNg<(4cE`ZI%)T{j*wCi6PjbXN0mmJ4`rB1f z7YE!LMTa3^OWpy1?<>_+7UosBz)n&L_C^mgkI2{bsEXwq)g!ou$t7x>=wB7}=i@W* zhG$H3&1cT^B*3)}&b|Fn`dJH$a!jo-psANQkibp4YYS#^qz^6owg~h@V#I={YB4GL zZRb%*YpZ8B<<%}}Rbz}!dF+n3U#1y&AM9Ba8ta%NkakWSLp^#ZGYI0$P1lk?XUE;{ z|AmIDkz&5v+v>_E)qne(0Idto-0Az{SZ;WPv5qqRk=TMx^vq&`Vi1PVI}FDmUbO|m zdt*+Fa03Y0qC@}$jVME(<06ht(ff4fX1{9`JeG_eI;1rcoq5iooJ_;d0k%h?`V?*$ zr&}JZa#LxKn{RcP`&a#pX+h=6K*k|Un;3re-JZF1lve-#W59xK3W}`silaIp369o3 zK_GaSf2;_b2Wkbv^>(^X{oxe{0zW@RGVdPf>ztkJ7Bta0Rj2$fN3&pKKPuAnLxt38 zSwSFYfl*J#rUW(ak;fu}QvCz0OoQf|0}PVI?M|fai^)Jg~`wSseed`J){vFEdcJ zVtcrsUJ#E`bQ1Q?dRT`bDVS{X8%`hn&5PVDRRx z`!O^t)=)Qbi}bzm=+1P=c_PtC5O{+0jI91HrTKO`O1p-&d_7Kc8-BJadHzYcDCeBw zcKBv-L&Y`GYlcDLneUztt{P-9P zry`#qm(empj<7q03~y~giUgU~B#Cf%Fa zKE6C8!ZN;ozG33lijSxLibG4 zD!cbIVB%k)(-=$K2y@sY*M42bX^t_w{ZH0@D9q*a4z5kr49k{2FoIva2yILvPP;_^ z^}9=R>iHNuRq6VU=+Zt@hc8!L@sbsT*j#kjpdWLUfd#j2( zu6J+o?oy`7{e+OUrWgA2u(iW2^3Fc}@o0^Qkzmk|c1nELLZXuZC2J0;-hqP$MO`3~ zk3d#wm)9&8s|nSw?t%q@HD~jkxi1ItT!)nTHbN&BvtZw9^Nii$B`E<>9d$y6F_W?o zy|8?v9O|}}WA1TF3FAY9xq;?%E{QEsy(}}{b7q5vX1^{oey0-c_SAAjaq|B3gJXLW zGuYxmu+v~er;M$Sqhn&c`yVyYvj{xIN`{rQoxg0-U^LuCrL zWOe0s!^(p8K`aE+0cTyy7s;?Og^WjA%bouPU@_EjxxvK?7xKYx6zym4C^hR7`f+e( z9jSXP^U9i!L7q0jJT@jqCKyJCSq4tY`x<1$j#${1dL%tI^HrFIv5rLcQW*aRG1Ki# zXgB(N8K5+mp_rL({fl>Ceu0T&3l@C^$9FJGGOt;3x;-m z=ZrmK6dJ+?eJV50dOnQhx5$p(+(fRow=sYJ{kLsqh_|Cfnd|Tx3Ro@kFHmdDG4OHg z35~3WY*EH*{p4%ti6lr5_HPSAE2JRoG`;fscZ!eG#YP=9?C*W)-4DqYL172ijLEi2 zh;huBel+`Y@i9uW;Wx6ryFyri+P0zZzqY57?wq-E4GTs9wvS>&m846`LXsX$IbWRt zOJ&z}J7fojRBV8i%P9K5Y3)ggV)|K0=*xhwK!bLwYs}Tk<`x6?An=+tS3fqH$Jm5| z>CizF&F0cO*buyKpB>P?Z45~<^nhbb6ZqQf641T$1^cEl4RDq(nkIP0>wcUK9shYk zUJCrNcB50Kn%**h15=gwn$fn8ziPq_n%ThKaBi6F5LwgrmicJ%U7!! zLTKLYJ)NRTnJtv@_tMbmRTcR9jZD`Oe{1Jy%pyc>at$e(<`wb~&;ohT-b|9u@qvoK zu5C(6%A{BW`tzK3Ba?WY7583%Iz%PhrZS)wojz&_N%TTbMQyN^8=HZdsrtX}wj4d;hqEg!2r#_AV!J zWo!6`UJb^eC+$^y9~IsQ4z40Uv(#S5p4V2EWlO3HwsodwWZKtBP+ITh)euJfUYOYc z*^1l*%@;KBt0h z(wBXm2-4Drrow)g9chA8r9$8cdb+RaXVXeN?CD{J4GCOiT+^&09?aX z9wP{&>p$SzN>Fj>%TO#zOo81R01}1d$=J>2E%OrohVLkL(86yZ#2D#lipLU(JkZ|w z2P}Y0mLwBryi!eU3KBpWhnZ&zvo&m(h54d1zdHPlZ77}c84ZzkyIxTHE;)2Y6We>; zD(8<*`pCJNMA6@A^ZF*WEMgtgaw=aVrrGn7s%Zyrb9{=-(aqmP+S?B$$Vqe}5~p*j zj0SN}{}I8)nkX~I6^oxp_|p8evhVMc8f!<$B=x#*=3B-X`ggJouFCDx?cOgfK$9`~ zXjXL3SjG$gD(DOvjcha5zm6aOz-R#>Ux_@B(6u%z^4oOe=E0CNw6R8S_b0vgpE$9b z_W+e|GQIIl?mTSC$)8ST~)-2UL=^3yj5B6wn^ zlXso#q2(6^IPPWiiZ5XadDHgiK|tllo|v^nq)g<6kLLNy=8}C$WeG1KpGnO2a^z5J ziA*1iPox0hX6YwHqVjK(6GCt;DGmBDM^rhtgD#zUrb+ypMN|C)q;7f<2E!<6Gz)| zP$B19>s93PF24NKDDgWcbt~ zBm~q{aIo~Vr{SL^pA!D{6hWkyThl^%$TQxzPteogx6~l^BL`{=tJovu4~68_h)a%$ zo}w44GYj6l*$MdE9F9pzfmwDgs3{imF)RRUYwJ@^PY8UptCFZ7T2009`bUfJ`6^Q< zEg|%1;?{6Co}vupP$Wti$BA_nzo7|OvSdjjwb%#L6ch5`b&OhQjW3g^kiI0YzIk}D zDJ9L!i^~F(-FOTeVc(QiH#=KG?lonzFJe^5Oyuh6UA7e8nH;GI!q{2-j}0WtkFP98 zKo?zijl=zDJ0l+JRQ0!Tv%ZDt0S%BRbG>drfY&3*!o_7MtDk(tZJl&IWJ|D|1hdXq zg&5%P3WJ*7OC!V;eT>XhlX!H|#~g~f){YSaV6nFdj)-K)gbb~vBAsq}q1)fRs$k%A zUR@Tj9aLFH7m8Tt!y2goI%;VAK1R;#TI&xJOkt!G0oAAIsPJTcnimhWDNyJ^aA%b< zyJ2q$QGUI>(Vp35T$FG4GF^346c0S5D8jaa%xe3mYC)}M&pv(2nRZxd6ju3d{7z5A z9=~}{G%3E-qkH!zRC444`4=U75$+R z)TxkKu|xzNDof&Un{EbL($g`Oe`U*&BW3~4i@|ncr&0~G&yBpD)CW2qj!tEK-mLJC z(!S!vQC8lhd44uLcavw;Wmmin*mHW}Kzyq)N&`b4?wtP#=uQdOm8Z z6{zMH{N!8s+7<1~a$s8B?QgwH^WUoI$Y}_zsBtR$!+v4z*MBbejayOi$?mnbHG(Ft zB`t}?+Zp{2bmFNpAd~%BhpsHH-${=X|5Pb0sO^E!DX*v|)sECBHxSAo&NzLu+L4SoYd((5 z8@gXH(#%ql9}iTZTc!dI_S^z<_Fq4e@85kSh`kIKc!q6=F$FCG(# z{>=-#)})WPcGbTHHJ*_fFsY?k4lV}DV5MbV`IhK*+a{;1(dQTf)rr+Tk~lK4BC(E*Xr>S-h|! z`)-k$1ZT&5K2wxr!zD2BV^MiWr^-VWI)-_bhLvv7h9z1Oe=>oMtQzXk=ve%>V`;a&9jwvM{Oj!zn0)=yuE-jZuhgXv2_(9qi5GDOes5|>xvwQIFRC`uF2kMV-k`+{|f&>Pk`^o~#a z)~$n`D^bpi0G*75>^#*sdU_^?^*+x5rkVr5wwiG_5(7$%>5JgD%TXPtH(AA{rRV7Q z#%RbQ=ifT*IegfYfy$(ljPJ91wTY7_WOWq%W)EnkchQ?`)c8f zLAsX6r*^o6YD+{XoJh=1XpDb`82zl(lZ(gT+2)^VZ#<`ze=c=I5~XWng=DLK5F&An zYxIQi<3%X{QwNubSfNGVU@w$)vu4$d9O>4r8)kyw+%xCEW;<9}u;1JZG3f~jG9%}m3^s%M z!v)DW-%(y31G2YZ>HblJxEz(|!Tn?BnE|6cI$-*Q0)UrBjor{EPNfv>ah`#JQ*`qDh_uipAG)J&cvvqBYAB^+DLIi@ytU z%8r-aDT-Kpe3G?y+{V}csA09r<%G}5HdhUtC-AjWFNE%oqgMMfWuj5`Hp!q=%10Z~q<2AiaWj z{T#k+>-qEN8(EaUGi*`#kXu8bzoCn~x{|$wTdfc`+uh{k`Z$F`%3R>Y;kqoIpG-Ub z;ju?ef8=R@=s#c&$6ZHqx~XJ-TFdtS^i?2MB(q7(2soa2;IhGN^4q-cK5Q1?iAW5N zue&*3&)BGjcT}u6WEh70bd0CV38#|@b6%c5nnEZJX2}n*MV-2K)i-~F9&9HW=2Ryy z&m3MM|F%MXzG(uEaYj|6f*eaPL9qw}+lX#x zE7hoU036@b6-{(>8eZ&xRaZHoy6RiE5MAEiLGzDaGDg-5Zd}r-gr~QaD%*Hwm5d|f zKHIH5IiEVjzS-n4#%egl1g+$@O{4=R!Lf_CIQpb$pl)%nxjim~AOj_?h}nalM>^wR zx%us^yA*xc;T9f89?SQbhANI@Rz*w(tKWANysvrlEvzE-?2D{ALDi@%SBF*K+UDug zRSaZmX;(J#XDJfV#eJa9v!*zGaCyxD$(du;9F;6orFb-dxW&eC0-rS2bbhoV+Z3E6wStzsd_HSIp zyWY{T&A^PHMQz#~i?i)tISC=?Gm)=y1Mva&9z599dk7JMI9f#2%|$r)#bBMiGc4EC zq09~XXGbh;B&uk5!@G6T(rU&>UkxxU$@EDFr@M)s9KFJo z+&t#EQbqbUve2tu$&E)Oo3&T}b{8*Q8fkiSaK$QyOyI^2Yc_lx#(*GW&ESVjSfn4k z!QG5YBem|3%P;po>+9vbsWR_MQ>&kR$nJMs`GuLG*-f*hooB830dvOO(?m>P!}UX( z!VeD+@iXPoHPp5;D;t|Ck1U@GQ%W}`>@@}_cXxM}?54qkTRndK7^F1A`D1W<0gEG! zjq2i$vK;}>>_MA+`f-zr_?X4igcXCBFL*KsCiI5BoEJ$+Y4GCIXw6RN*cjdVJo(?eviJ0@U z6k(|KP@$sQ@dJ;RMms(}K4L1^PvJHUtIq)}uOj_A)dNdrtO1P+sRFye;v_%|i@~_? zAB-b=U^}H#rul4CH6le2go3}ZbaPXUkU?VlfLGkYLg!>mOK@|&%*-@0aBl!X3o(gO zPVO@CG!QbXS@N995h!z_5oLdsw{E<+GWXG~^TsD_SOih5ziwTEV;f}iym3?>tym$1 z2)ydEw#FUH<0*>d-GMGfWEFeu*r7XWluYNEUF_UcO{Y=KzEd+Hf4GMX)D$C#g0xJD zY3ngfve)4O>qv-d>IUbjILwY_(llO@9tz5t90S}R$|R5te? zM6g(Ub@4Qq%2aL0#MQ3gVFuT|nW*@JQTWQngCUVq+&dfK0v)kMx z$_X_@uR0E^N^+YM?~+L0q(`5kZir9}d;< zi!=JHqq*q`|DtD+ClOcTHssQtRE%jNbnli|)Ya*{#6UX>gcGo#a;zaz-avvOVmD>@ zph8%;X9v)7Zk2DC!4R{Edcy#9RqPsfLY zLvsdLv{f@yW`@pYs>PIA50k3`@nSz3H+5=b3WH6IHgKF-LQ3ripHXa-pFgQuKNjli z!&o>j$H&tn^bT)YV~$QP^lz__F^IhKGvs6H&N44)<5T(2V2ROmoakXxH+IwrQQ;uo zON+o_kPP~$5mnrqh#Abw30=ynw{}rpY;XR)3i-IF*S7fe+WcqSEsR6#YnSohznq&e z9k`Vbc^ABVXPMalXwR>E z%C}F7A5~A0r@&%rl>7IT$Q{ z{b;K0kAR z(!3WglnJBQ(l1^sVXZIaE3~(9oH%vrI8c6ioM&V;%Tr^N?M z58iX^*bWMHQNFzlJvT+iGd%FfgABCjqE@DKr|8xxBBel%BW9EETIxzps?&enwel=} zoDGKYGw#nBqCn#l*8jQj*!vXKf@-toyDf4RA;0QAw)sH=ZnCVIfHwitzg{mnRWYvK z2Fy*2+!Kljlh`4H+$?V^=E}{mQ{?Th9p-)7ShMFp(KB;0=!a%qTvi8MIEgY~50N7j zkYWuMH3#6O@DB9-(e|0!N24A3_owzx$^ECD{k62hmL|?Rf|)dDi5CjYGfVZuqJmGI z(hE5q0bgON-fQ8UISL+*$OVnQ78FH<+8zVBXSCJC{bPLh^d9-PqSS`E?+SI19qijk%p4E}7UM)2=@v2T7nUt`tR;`U~I%-}} zdfR=`ZQGX{kJw#27L@5NS znCOgFZShoBJPPjD(}JzpaM$n!w()VL$who6MP5Os9sHvv>@!~If7|4|)v8m&9;v+x zu{bl~qL-IJz*TM9k-8lwyWZ8AOs@X@6~y?PDKAEL7w zN?z3MI13gRMKsaTYELpgF3?*Uk6=;wvG3bzU1z_*T~Fm!lmDF|7zv&a8iSxrdx>yR z_tHOrWvMMH#inxyGaKmJ(WBnK4(%Y{Ih1KfhkDeMBa~~t9QT`Gghz#&g3-M8ip!)% zSKHj6VZ(yx1HU#xhHXEJUxRi@KR3sxX_C%X?^E+siM&Mrt%IG}HQM20hE)$war+q77w*aliRfwR9~a+Th2JPOtVi_dcP|QKA8q zslP~VGCh`8Ref8`ROuZhrLK|8MFcaSxcEviNnoTSSvd|mu+HQU?8j7t))wbe+^Q&bd7D3TWo4nka}{< zf4-w2diHt1tcOWi|L+YC7?LC|Wx!g&(tqrGQ6P$*dG6Kfqdy=fK2XVnNM%tFuBYM6 zDtrJ5-}>Q5#4O+5&TxYW@9W(1sOqp`msHkGS-9|(%DTHpU6`mf`O%i4Np@3zc11;= zV|*pT#fMqVVxA(k_9ohb_t1dWFfx0({00*xvzPlKlm>a02|pr4U-IpJx$mJ9o(yfB)xhWx)w_1V`c;Xuo{>_RqXOJKUhmbPg3UQ{Jzb2l4al}^GS#t4p}+SqjVm# zMt7p>ku+$s!MpeFy+z-D1Cgj7TF%gwqzx`8!~rOp8lWM{Y3A=?8)Gho00g9zu&BGF zjlj9JsSLZLG$*L0R=iHHgLNU~bKB;uUSG)Bm3_3-8*=i7>SS?ZMrP$da@u7kiOE;N>&21S27BR?lh!-;$M|J5G@C0shGHhNMUiIsfu)sQw+Wh^HFSi zoQaNujg1W-BK*^8g(S|<5);^J|4IA)gC#G1-T;0o*MZsDph==tghP=^2lGR3@vG5B zMOJ1QO}&bzL6os^D|%FY|2P%g^Jv_+f4}LnXD~fYe1qwRPaGggAiW5R+`t_fMm;cV4FN2(Zea{AlUpc#T>T0 zwdOxu8h-e7$%hCj{URnvI1I&l5XQN%AelbPc~4@)cYFe*+?P?T{uQ(CyPi0FxO-sz zhV|;9*WB5icdrX-uoN6%;_hmh%#2iHdkIzc@QOnJ!MKIJU-iCnf=9i6Vn9gLThgQi zCjF2wkNLoSiHe8EK7Rt*_KSEMv~XXSr||LUf){(26f=QWav9&J^tqDH?319Vw|w

    uaL1UEsSZ7!etGCDb~nC2%aU{F2{zf;VPt!mX&{#BND5cKyA0IbMCEFl zdy_jelIW(TPY8wZTbp!88pCQW^c)QuFCZ8BR zMW9~!$xvX#=tTGtkdzoTgxf=~v#rN;N$(R3mDDxJ1j!!3o`CwA0rBCF6aPgD`o~cD z^TmyGES|Ea0?$tJwQ=|@^`bU)W<`x4__{oAZ9 zCdOo_b5U(>eo1Dg{!NS@8CR!cg9I|}rPhG2x&iIEiGEC3A(MTOImz@U?F5g~y`|)p z`^_+|+Il69#0UxEqT<-$h8*Uwmfi1?QzK6#yGTNwF0c8RPwtE20mh?VUj`zQ1&kN)5$&;f*M{ z{2p_|U%zcfWqT7v^kBznUZh>nF6t| zSWgK)hd1QBB&LFjTnMslB{DXTVnMNg855;95}T zU0;cykg${a&KdUF+%~E9<6294-i->D!FwEIJ6x+zRDV|ihF4zFC%^o`yxmtHKD?Y& ziMwTME5m!_)5G4;>GodlntB^yi2b9Lx;MWX{yg*4l~}Jbi472P+_Gi;d0LU{DqZC7 zP|it)A8Pq+D6HCIP}O6?sE8e(Q+Y5|exP&tFYMS;HND+ld%P9gPqh^N%6cd+f4n

    #+9yhE`7}4|+)C?nJe<$`X)snY;q)Z|n=c zwLh2*tu(53VRF)ZBnQvhKibWyF*}TL=6ZejJQPf#^hFkZZerd=Jaer!G`_IPE6!JD zj2Z4+024g~L)GIMS4LtikF4Um8CUzsdRL7amkJZZk74H*&!2B%p-Tkb zJzFj8qaG6jNbtFal1FAIGu~>Rg{q-tzvATIKqkLTxE1d9ouz zF8Uq4gfVDl2h4hw7vJ8t=0M!sWdbITrr*dE@LG4~9Xt3i@mH*mp5e z8{aG};?9)F5mi*A+4DT2B-BtMq*9dYD`|at(^_}mDa|Vjel$KEFTHBq;8&aNsXl}+ zP3#UFT{lsi656z$V|7Q5=|F@sBjycbG+->={<(1pUl@9Vm~Cg)|9Wmm{VnXGC3M)fJFPFE@=AG;7_Qxnd0mFz5;@1NRiYT12 zW+-cgWB2H(4j?ZgfHgB~O$}~nYFd~2!|XV1vCEM2Z-bn?y-WksY_G>HN(}D0;LhPr zS@=?z%lNybN>N9ObNi~{EBl^A;i z)iX4Yl{Ql#I=X(_3>rxngn51epFT6zozR0#-<)@sy??*{$dT5tBs3ni^B>zTX`VX6 z%%VJn`j;kIp@8-=Idd5$8vU_#9yL8jT(i7_&RHgZU=~DuSVy7dkfkcK1U7Bj)Sc7$ zi9?=SP59)nm0_*cgd?SpJJ|AU8i+o~vPSKeq>0f{PRw)4iTZ=#u^19MeQxbyz=M6~ zT4ah?u3y7N!0B&Lxr1TU3TkSL$kb`$-^0eZd}DNrL@U=?!6GAr zJ>t`>#`|wJ-`3^F?dkVTtR!3(ya$Q0mA;fy<3pCk;<@Z<`ciR?PPFwgl;UFQDfw!zJE)_$f8v)tDkg|xqrbm@ubrf_o0Pb&jC(qSrqGOYonmYD z^L1_fGVS|uwf;4H&Ga|;c&}W2J+OE0-f1xoGa_dby4I)9nTdx=M--1}Ny-3%s=YDd zuKKpF@wsP};k_Saf2PWe%2v8C=x9C!bdOl&TD24pU5}?cy10DYnc2Gc{WY6y=ePh= z5h3)s2DV-Pg^cX4$uun*bQ!ZMp|w(^&?-OW`rJyorG!cY+Qd>L?*?7WuK^t0P)=`|6Fi(^6*+=F9_L z$WS=A5{VKJ#^)p?w?Nw21+D?BZ!Cj&ibpaFp<5v1Qs~H%Q>e)XX>4m-LB*v zik(4xG@An2-kIkYwc{kEgH%?44DPA-&umCfv3JzF1bZh*E#+?Q;*1hSCu3cE%xpw2 zqsWV}{4(VbeHaM1(!&NP;t9rzDn+5S&F~>H4?F3M6nnfLv_NZmtdaJJ5tg4P7m7vy zMg_^bGKJT(g!|a=v-YRHhU35Qcl!A_L-fqe)idm4W@=VBTSLRwRPB(9!GhGbSCg{Cl4$T&dlmlUx zIWJld>c^4zmjtP|b3jXPsSOK_d0)L}(Dk_(=*%93|F z+K&w1$*@%B$o8>zMcX0nKB@jWoD_&}+rgh*|KtlPd4r0t_paX>HPS~5kPqSjkRm2R zYKaht&NMQ+VC`AB6?t56K#c*b+Hr15T%zbAlQ=tSuBu~GqQAGU{Z?lyrO~m+g>JM5 z16TLqh-7WbZ3Le((R3iqA1RWZx^+_lJ8QP#0)Wv|S|7z*uREvPOl#ABem(RAk=&wY zXB#Wf&&=-}+?u&$ssb^9nLilB!a|k}$XcHhu6b%2abFu-TCP^2Xm7dUZ`|m}Cu&`2 zsc4Hf-L@M;Kxp<5(fB#$J`trcX&lzBC~mF0jADCB9ZgW$;uVR6XQ%DzGNF*TpVhIf zG_m!;FW z3jtHqE`;1UJ2&Ypys7x`04#IY6?r`2dDr0>S7dH|B5BB%85EouYxNfSZz2V`s>e&! zHEaNxQM@z(d4E2obJ*t#xtl2gQ|EJ)F~Mb;O+3tKtu-BOd~~GR>R%=zSXnQvAAv-{}IDd*9NT{B+R2&9k09qdx_-Zqdh5Iyqz( zG96feZAsI{x%&o?o$f&3QQAfi+TN#B(2a{h(5%%{wj(21fB0~# zoKJ@pbEs~P1x5pDSjW=@TUW|(SNb-aTXBR5@F7;eI=<@D-IjQf0OBrxN}q&JMp==F z>>_pe$DN0lMX$9oSmWZdy$t;I?_^r!&A7q~%bF`VbEM@=q0G-OEc9d@Ji|RCyn(9E za(3JoKvu=W23JcM!#JnO8<`6KU=V)CiQi^Le1EJ`yEY#E+&S%ZW!gjjb6ot( zyxa7hqu@_>ZlI~ztiI^gF)VGsfDl%NyRS!9yLRoyu09jU4ZI7}ExO3;IRMSWNc!t~ zEH?J?Vh~4fr)qXRkMQEvl~rYD+@BKllKrjoGgc)#`L#it;=;o2-(2pweO3~Lk23kb z>p^jKV?l@{U#!EXO1qu^mib(=Y*hgSsL!a3z?U7_TZHJL?6FR+{p+F$IdXGE zX&&ACjf?=C+kU;)njG1=QO|J^C`+6DV3F zv%=7a+#DPmN(yO^nQ!Qj@ztRS1BuME{ejr-K>KGp>=K=mpvQRdrCLFY12BgUpfEGj zK1K%0a)42VthbDJX&tt(KH57OWdbuVvK?kV*+0?k_2-{A(cUj%NPz^pqG@w}e1_xd zFBb3QVa0GKeAdJ}VGHK%Du8F@au)qH_B27v{U3LZcl$OF@%FtygElyC?-qW-xjI53Wl zbWb=u@Dl)(zQMbhPY^L&_na-VI6=o*ax~-Oi5H4y>?7C8WLUSmzDDh)Iq9M?ftk zz?n6~U)YVJmZ6%VFWhD~owm@)&*v9Kr#;+D=X+KY1PuNdLN6?Ny7B5VPAnOjez?EQ zM6c7Adfmz{zRLK&z5k4#+bhAeVTWH#q+W(#ugW}K4OP-^yY?(EFK;GK4-TPE|K%|~)w@jC2We902lFZ?E<p#;-(qfLi@ub|HVOTBuk2jG4Ka+)@I?@>}kdoIQxRPP$5 z8Tf&J{=?aZbogJgRZXXvShDrE7=>mc5<1{rP9(+Ty+dv9bp*3M5_J043p#K5U*^+q zD;KQv5@Q9-S|jTOG+t)6X8Bg;#s@?3qNlRCbU`QGLsO z`>2RC+sSS@b>WP&yT6%dXZKr!20Jvzz3yKyer}mg|J=&A4)y%+nZ%qKp zyHnkJ+A6!-R?D@2OUa!72x~CMnM(s@ju$mHTSkVk=s$i8EIE8xhWv$kcPY)5Vc@jx z|2fxGTlG~?F7o`6NF>~bx}Bb*5l}h966fb9*Ir?@b=lg`-Ja^dPuMqY)-1=qCryt9 zur^|ywyPoby<^{OL1au!^UjkpGrOBKAD1A5khR`^x|eRNrQPUG>tSV!8F`5k!;n9_ zLJ`ZrDpqjUug592lIL`f__GCDxvF0S!_EReXgmMgy{onSoEDUz}X0v&{o(}Ts8W9~GZMs2QS1C3QIm{X>e>IkmiTQ$g^O8EMt7-qnwqh*X zUH$a13mhGpcJ9Zt9ZW;>XWiIh6#u&kzv90)h(^c;IU|8-ew^RFZ7GMC!PeA=cR z=gut;umSH?y=%B%4$1%inltxNB21k4`{)ZqML|1n=bKv&1!uMSDSTyK(8%wpw{MRE zf0mzFjubKLWX*-4!_$PBzw7El*04jgn%yr2pQR#1B!D6Ey0Zw@rdK_sN$!%wLxr}vYG;(WDlNNdW z=FG-iJ`7C}h6D2S8jVg_R?kHwkY-e@MVhF;+tw&@7fs)31@m*Z>VHkmKe}^chy@3O zz1v&yp=D+^$9rg-6BTgP`BBNY%IX$|PXA9SqgU32JCZb!&F10Yypps&zkpRZn*Mes zZC>%^#^&KIWYPt$zet!9K={ZkC&-Nk{A!mCJzd@>Z}Nn@BntlEgVgtJ_AZS!@6BFG7T%?&EvQGJg~fZJi0X%elsXP^{eZ@x`PT?1o{ZDW$-R4_YAr%i;} zd*x|1zG9*}D{a$^9EYp#+i2VD>moBP0j?O^JBmS}jyg1nn{xn38-|-&_3V6{RUI zmpRa~+V(r1p7-FowV%l2;tzWJ#+H_FE&1m$Uu8{<(!fW{rr5}d?VWa9BR*=$tQ%1r zL;iV`f}vWiPPaKq3X=8sh~NJIJ5ygz1BMM?^5nfPh@x|X^h7e&!shlEUqSs%CYMLj$G6At2@JdiR%W>8@gFzxdo@RHNQh2`rbV8%UzKE#o? zes%A2upNoc{cy>`*}n*_zCU20x5sml((^o3R+t#K`+v1y(B3p|LktTLINXLv=WIGy zVyd#nnU3USEZLZ8B^6)4J{1ueow(}30Y9EzV>&Q)iHwAk@>k{r;9$^rc#ymUr#9^N z8V_XW9gIs^W~@fx>!&h)Ul*$Mr2Gzj4ph5RquS?vc>li1m26ITUsz&^KmjH6Gz~ZZ zu|Zdrcqy(sHIE&;c11W_aAXKtVCi1zjC}O(fK)y#VAVL3`%mvFXp-wQZ}{Bm&4F%DG#& z(<-a~Fi_s)p{G|aN6wF*PkY3{%4b3c@t65|H3Aw%uEL4e^xMyOaTICDxargPUEO10 z(%BW4>yE}ffhOzWI9FTp5rlusmK(~KYXrIW^{7~cIcE_{E*tG`)RO_|j(Y0El7m@S zcPaSw_oQv+MTik_;?FHw)I{xwF^FO7Us5>@m&1;a;+jt-W5_LLF4>r?9vayJ*pSJnk|dM`69A?I8B`!&8*I)Dm!0gIt9ys=?CZ5`c}V4ftF$ThZ@NqfSvLPE zwdBOz9Ol{rfFPuifs7P!h43YgPEH;2n={62-i?17lr-HJI1+CRda~B2n-jCe6&M@F zfQ;~1I?|tVUBSVrE$dlb4$)cn^hvIPjiiJ2dSP0%m_0Dqq^29p95!JePh?TwR)^sE z5lO_)lb-qF@`Y+1J*&@S%;cg^e?3EP_9Xd35#2eBcBtH!W%Djy}HB!LLcusPFn{6W%;Ja5v zgF)jKABUt(9zWkqleTSll9+dr#oD&uuxHRVk@f!gDeUw?tf4sL%d$o!Ee^c(J}>FH zSfLmkD895>i#hCE$|P@~(|I!dWSsb>;Wgj3e3fsKv01_B0(fn z$R+4nh@T*H(0_km-og!v(U5Q%aLs>#y9r1id%mp#GYCsi!2-Cs1$nW=(Ky{R^AS#b2}21?UgWx*HIuKw(iFp;bzI& z9Dgcsynh--vSwUU2AZ~bKRiLipMmWW2eXw7fGV=1`~Z9d-;b4(O;B!b~5x&t{?rq2u6PdbejQMRbi;Dh>ZGVH90`YvB& znqY@$U((K4jf7-2b!8a#!$kHi!<>|X7_mPayHv^}1aa9iuKk+Y+$S3Y0&HR`Lsln% zBQq>QiOUa@;HFELT;r?W$XFz@P`zN*g~;J3FI)MihOU%G*bl$|VBiLE4C;z#b{<=~kS9&hhAcOB{KC)>&i|lF}k0K%OP7;3I9u(@Th@a$Qy1J#*{XtAjF# z^;<;LJQ@`8BPEAXCTFra#?WOaPjK}hob6g0lv+1deofto z>Q6!zO3nmxXi1ha@lm&66?!?G>v6wf9pW((Q&Uqn$M<`Ks88aeloaHb>62I)p8G?D z?da_+p?Q*FP&Y*)Xk=O-ZIX)(GO6pZVB)@wdG^w>MLkL6`gcEB7YXaYA{R&q)_B~MMrnya71 z!Xol{n#HI}W`JJhMdr?%*E!D}sf;`iaw+{E2N|PXmq=Yp*Ai_B^ED0prhc5k32+(_ zr9)E)Fp@|Oz&T|>&w7du$TVWsHgJb5yLx|i?yM}ht}vX?lQ~@3tK|vXN$|_ zk6oYX+R?|5&e&XJiM!kD9L=a_k+CG)>PmZ_S<^f^erU&*d5xc!H<++bWU2^QW}I<^ zUEx&m_|3(ndPUM=86(s=TL4-vPCrX0tB*2OQ}SIE`FqE;@3-3hn8u@bWjI;w_V~LN zRgDp%R{o-X21ef z=H&I*SW1IEuvJlL5X(fU2SCK@BVfED=S~KkgEe@@>NCl5Mb8##ePg?Q-T-~X5s=Ly zJ=i22oH&k=DHgw2s~6J=*6^<(n;4ch7d}hlauH5^w08}8reVttjAxS1`&I_OeARwi zO_9XUbbk|h>yv(V&>fO${>VZC=pY(*wi)>#Asb zV*#;P_$rN!jv`QW7JwF=w6&XyGMx3d=iosPMo~xwr4n#by;i-0d?kx_Y0aO#q!^9B$GtVpz29KQt# z(%}n(G6yU$pFR(uRBEZH8;I}81I!9_WxJTY{|CXTBn+_Gcak}~t+Jp~1Sn^GexB%h zuQlj%JNM$slA~Ac*2;&COkg8?_?E}@T~=gz*#n39JhF{f<8#nE&i$X$k2C)|pI>U+Hp%j&G0bltceNrEpLSy}e75)K9!3;+$bTe7{AU^$&FW)&avIERy z({K3m=ikcALhx^M^}M_eA`7|FWE{ljD+n*(nJ&Nks3dbz_&2b^So3W@TlI+!Sp-1T zFwVdv>JkF^8F~uSFB!qMlWQ@X%LecRalD!^F(Y_oX#}I1MW+9;{v17>N-s1cBSMB?vQ= z{lHh}qYoyWSWsY0K17c=s(p~T8BHS^Az^#YslZr&H5`FeZ`AzHvqjBBd?1!=c42WG zYR|76flxP}aI5q=3+l0Slfh^Ks*rdzD%}%sT9vq`j|rT(P8%k-IJSkU3jPC(0)YIf zO1REN4+G+p2N2VYMQo85@8B-gDz7EH4k>GERi_8ji@y28h`(J-9GRjquI~I8mJsC+sTOO#E zv`dH{Yea!h`sl@_-1=YoCm08eKv}xh98Enz0S!GII6zfcjEhmk20a`)N zq-)numbUzbm*7T7zh?{!mfCo44Gl zw6u`VaAh|WEE`%BXGh-SFpdG;hHoNIE2@cTCS5>l=NwvMlh|X#PBEVi6gaFd%v+0(vdr=j^AtNV1JrE#Ju>7~uGbPhgp|Hhp_m z)N7}P3RP@B6vr2ANjd4|<+Zs9s+M?4qPl*wGl=oBE8fLIjrJnFTY@&y=*=rJX=aom zZ^bLfTOGP_qphWG%mX83fBoufJKp$A|GlWl_*2_bPP}(@aaFVTe7rv@h`Z5b#_7==>dv$Y^2AA{b`wD=pY(z3kryW)PBkF9q*Z6;ph1aji1 z%5(dxS$`o4NzYkN_GZn`>fekfj}n4{aT*#K`71m}=~NvQ;?x>AH_=HG^cPIw9%{Tk zaZP$&R073bm~iDRb*2)JO?`~_o#ncT0|pGxZn+3(nKUVfQa+3tY1Q6GhX-`I+vP z`}SQ2F*2?@e_6nK^>{GOPjEXFAUK)|`_V=Fa~DkHfYRZ1NvZW3b)UZChv%@SrY5U4 z&i59-b85B$W7omO(XTG(eiN|8NO6Bmt?eXL)!aYo+Gt7cCQ=|o#lGY6Eet6rD>HlW z__0FHA2P=R$D3T*eM9i7PPf(;KKx^U?=xtJPjGaNA#7xcL{{ebVaC0CCv6<|PYuy) z_ImlqSx_U@7#NI;=|c=)fGCe~UBv8X^6E_x4fjw|4q04zdB0##q9%|6K+59^7pb8L zCISj)01ffXI`Q^dIqSKSTGUmC>*I&6n$4L0uG5}9>F?S$%qVYg+m_j499}=0UR*3;dup~vRXYFb|_FB|##_=rIxXyhyUsT1d( zWMxU+%51okAzOZ)k}fgi*I!q^`9e`B&>FffpO4&_TOuJTK>6|!D@7p- zXe=g-@HsXLT~h;!_Gb4p8m)WV5@O{7+|wjvI&yirh~rdt+UtOA7fVo39}jGK$o-2fZJS2k`J%cqE>fQ^a%ufjZ0^0Xe>ePEB-1` zj1QHQTmPZNXXH(Mtk*d^K6nU{rabVfPE6qv5#Rd;+k81I`I}?JJu2dP-^fRHS1krk zNxWHg`Y;5Ae1Hkdl{U40eri}wntTU>G#N@+IOYKtYdE}Q{Z9y$e3N*I!7y|hLJS9e zv8SEBG#a=jYKAri4jbK@vhLg6*7p`N=xh@YEpdQNdPVdk>kOY+ogi@d*QJb8}bB8&l{ zzA==D?nCFicN!}1pGm_5H@Cphooim7Lm)YMWQzb^;b{d1m&2w7CQbW$PIX&ScY|Io}E{Koz- zrCGGmOfIXb-~}z8bWciCBLmC*>0(FIF5KqEn_lUR{I_2VXYfj!GW3V;pqM2^gH!5h z!z?o4(8tnFJuLk#F)?f9^4T469uJM*#F_ZxX6DRezR?vwI<+fWmkd_V>UdmAx|h5| zWlGn*Rx7&>ruG4-4!SjHV=!>n&T`>9W`PZ8`k?Zt$_MjojW=SwiHpZ z9nL^55c<#hXk9Eer_Vujo~&#}YaseS_n@w;^S9`a2D!kb`hZX=ZMXqISVoLWLLU38 zDv6Uv7T9O&=}#)03KJ<-Ix(zsFsIkW#=Eno+}*uPj9SGYmwF5gcEwrYByZw5SxGyz z7l4PqQOIfIzR8}=*M_fHdG5DQKfi|*e5!n%0XCnP3%@T~xbS`iOw4h96A2J@noSol zDkd+oxGwk87+33YCydKt?Li*;BQ>2q8-HbSI#)GwTExC@<914_^<{FGwCVg69C-~CB#!@1{`kO!6XG$)x@z&%N6coHm2Ol}DS8R0kL{!S2w`VpjYu0)K;jNf*>QAU`E!lV`% z5UtIju7s0M-w#~|NdKuFj-(gT{hHO(^}CjhEANMR@r0)|mBLo1*qbn)jgNIK`DCho zsI>JUv&}u{rQWt41i+fUb=3@o)iXoN(?I&XgS5t7G%Rv=na~H!humOCt6d za*+vZu3Dt}h1-rGq{B{qx%2*%gKjB-s|*dF?LBfxC~`#Pq=N=v2>dV+*#h545IOqG z$^^IW7Rl_*j3FM$jI;5+ALf)jX5Rj_OE2Ck&7r2BG&A5zhl`i14DC~|2OQ0!9H>I6Yt94RzPlF@HqC24OU(&3pHo>4Nv^S`DNFV> z*iKcnBR^}66Evc1mvuaNbW#dQ!GPSc8Rz3@bvtRw{kF4unMoPYlSoNvOu^yKNY+br z-HkysZxCkhV$%rvGfJjbBD@vF#9=yIgCp!z?*eKJ0Tt0yY)jo{Gq1>!uA{1v^6k*2 zOCwBLQt4e*@9UvbJ~H(MHEUxhR;d?YjU?)-8^2wY+`7rNvI(3($^D1tSgEnb2w=va z*3*sA=$&F6@g#-)cTc&jcQ5^>4gXGvy-WSsg5DRqp@+#lW8x0N zlp~9dKv2#FV11L+K;3Dl?v2i$usrnAB}=2QTHTr)GflZkn1(rM020CP7RIMS&@2qa z9)DLhnx1qQNd-iS6Gk7W+=nqjIo$|xz3j?FGe4F3_LY|h-v0fw=CwK1m4?`we4wz} z2tWaf=WF*Iz#tJLT%mtcZ%DXN7!;N@vyWMVuIn+SxTMjArnkGqz1qKdtW9f3eqPj6 zcQsT-$+lQI`O;MV6jjq>8r_y%C3#}ESh-`D(Tlt;AuPzGFy+t=C#L|%<*|MD$HnoW z_teFuS(YEbi2Pm=5N{9WbGaE~>kDH7V`r`jpSRVX(S^{}LmljP;q6{W=Fu8y$%SM# z2)|qq8;QGVoHjn|pk{WdTU{%?m{&+kOjg}VIk;7FcjHfLMsj8k+fLsLVlKqUKps~G z|Jey}clO$tW=Q>0zG@x4>=fu$|H{j1%NlOFU+1`Lkbdol=0Uk)B;@JeX#yL;ldEXu z?y%|_g=s|eN4XSrz4A9Z0m_6t=|aQ~VWM7X z#DN9E^8)sbk9=_$#YlD|0K*y8e$tvnxnTyLsh@-sn?r}(KsVLT#spVtA=choxC zWUC*2>o#}hl50vS&Ckc3o9G%KQ7b6v3LIxUAzJy_FL91xmIT%AAk7pdw*2JShoL0 zXWIX$wn+0~Fl|#~-K$r5+Gn>d|6qnus$7uG(7zzVhI%tI&8VEOIg_`vXgB8JiGcC`#%3ReM0x~C`641abHbsdu+6N z_1HsK{sL%6O(^3Iiv9X>LC@L0h(R34;?auz5@75seyhAJ_;IMySYsWimD9IITSnf+ z--P{e2qGS#72{)PiHVZh21T32aq60KmWXr)H_)S~2k$0J%VCXaZawE76ELWb0d{Q! zg_+nba;<2JcsWpF;y63J`h#10)6i`7-YM!Rs{50iiMUJ_rtm(FH37PrWtc$ZQu`kU zMLDiC{RO}CLd3POPDA&tNL|DC1%_4C%!D>5dGE7F!lVcn5g|tt`4^OAlSrU(Hrf`< z?!@Ur5Jm=R?CQ)BEkeQ^u+tfBH$(rs&H@oIJf+)!FKunUuSI>vXuZx=cI8W13BR)P zKPhI~paI1$=h1y7%Lq7V{H{(CDkLFJpRO8r-SY5MSwcNEP2|EdG8AE{^^Fwi%uZ|H zG~)Fl>SEr&qX3bT^E#qVambJfk98L>o@Zp_Z#Qsd;GubXEpx+HJOna$g@TTKKP{>r z=gCi|6HKoxmQ@YHdR6Fm;7lZ~H*lH4Sd5ERqL%doz~t~lDtDAs&o}1?r3%dGSluNT zMtip~#u}lnZhUqc3V4TEqee;d1Z7tAIbKR4f?XN)&*1_NRQZ@VSJb3U8)F z)c6Ws@`WbmX?K}H4l|$DC(~T$mMAm2R zgfD!o!*#v^An7}9KibwkcLHu*2-vZw5>lRb4l{$nsKjOBjBSlCLUXX-`m`un1!;HR zT)^B1rH)+OIH+l!H76FHul=?ekcq`8T`ppH5?@>S* zQ4(15W%DgdH02na{DS&I32BR>+ep=NvH@rOAvzmf;Ew{va&EPB1649S02RJ&pC73 z571<-2ig0Kue;PU=?j=n9fCm1aCszushBWs>982oeEY6l*Q-C#QuSr&NJ+ji&cIRp zHgk}R1vSS>6Qm50VM9sWA&;zQ#L&7gwn!NsBqg>uAOsbzo26Nu(-wFAcodpL1Y25b))NJ+=E)Cpm{2hOec1YvvG6I9Kv8g z4C91)*2kx-;8Q^-?49NUR2An`HbSZ&Nf`wFV)l`i)wWMXAH1)pOoALJ2^wYNy0~I}C;F z7C2baG=tgI=ZAHM3#||d6H~smkvYS-t?OK{kbW+V~VT(}Z_&7H=uGKMKFXJZn#n{Jl_kIj3tcMq(VrE^F zf-_5+UiCHD70=tDuqjP&VFL5MX4ZLuQXQ+St{x*OY1U{1gDJH!O#cP>umvGJ+juzr6oI6>UKJ}YzzCvT2uQb&O6BMYK*CZ4#mXm(P;Ustg*^a24J)toA zwvN=_$^I-h1^BfJ{Upw|i`qr!Z>Q6nyy_Fu>>_s^e8PJ-*gtVOaV!^0U0 zjC?V2(JcNjo?F}QWpr$Ymj@6KYfu8J5S;q-*?O3C=u#9ICJH}~0GlV(XQ&Udz%y7&UN43>v++Gk3gh8H= ze>CZ>ecD|BU;TRZx|n_pbg&8{eV}9L7K`X_9VNnEC?~u@w`QMGe)U$^2Ph%?7E@6V z{X2+M^X!<}4J0)FYF~hF009SGiRx50dyD@P)cy^OcapwD)NYap=4^KA;^N7U>o)69 z))rcs#ue3mS`t=xKCC#6>)59$jWJ`)3L}?wV!jSl->NB6FZd7@D(;KR)ZGZPkZhS_ z){{sL`c##WgPhFbTM&S=|CBoC%&_9!cSM!g&c_T#ffQYIX}Kv{y3BC_O&L`fjZ*(?seg<=hVdZ%Ska+ z6)ZZu_Qs}WgK#kgxCKAVvI+UFc+I83>bZ8oR1z?ho_!glw54ldVWF^c5!NRJk8FU| zRDug5@ONY2&2Jr9j<9TVaOoT4Q~;Yf&TGk}@BJooTmAWS!UM`HB-9H$0KCq()x2HZ zOs1~jU$ErWi3hQLrJy!PH^CFpm$atj$EtM?!6C>P7=MH29eIII6EXyEaXWqc+}Iz& z8)Z|GM;yVbd}|hIV#IX9Qzyvh>1HiV83kwN{d+$Kc~hfQbZrHd6x(#_0P?K*@Tg$z zC|v7$y`La;z>|Y5AgT>!3>CY}`_;8L3y&w@Bn-)5wFshr$(z@iQ@B`hio|C=ecicb z#V@~`8sLLPA&jww{6~RkWDz-8%!m z&WXT4FAgV&CmaIv6Mgq8ap()Z|HqFX^MLo^iQjr_Kad@iCJd8V|IoQbN+S_5u}ym| zrYgejJqSbVA{C~1{hmD&ny%`bmS*yXyj z-#-+S*O8Ma_nN0Sw%D}as4R@EBwa-K4E09^evTZU*I$Ia*y3zBCk}6 zk+=s0y^ZEU?hDXuoa6_?R0x6y_b;r@XygV7t-QG*zJ~@Ak@1cVPpum^MdS$z> zchuy<9yeWC+^S{6MqE!NP|9PQU{xn7+~uTAg&U+SRyy(a)(5k)9caJA=K_!vJbbIdQSL$UAD3=Or-ZsdOR8sn z)vI)jrrZjBeW|0`cjD7a)2WJIgVg-C*OmFBFk}-}3Vl+eT?JE|lXG1{eDoN-pkMIB zA8qIVLd>s*Bn*GWXsc+rl2Z2D7Sbh!hY3u#mJq*1TF(q*WquMB*@iUAi{~0tB3dA( zK&+D)zXeB60TQeG*PX0aFO$N6+uQ1KIJXbXT7QcX{2}4)0WTv9h8-(noLLTFmayc6 z-zpkEEI!!^$)2W5wNzi3$7p{1;?^MSDUr4{)CV;Maf1&eqH=)br6AcdTQq2JJslWG zfb-RgGQt%EccZ1k&pT>{Jo+3cmx81PpGgF3Ld|Hj1KmhyMD#dW%~t$q>vK|EK^?AJms;ZXI9iCR|)g%qW>FhR_N)-GJE$By+b5AU6_ z63Zok$=G6b=9aer8-pS=TMy8|Z6KSmr6PXD+@0IVDna!l4vUg>hmoxIx=b*F?aTd# z&xM;k>&LgIKi~d1kdiew_6?v35;+}zIWh|IU$P_TxhA&!_qp%qX ziQ50P;`fwU#61sHmQK`^`@nF`vWv9NLeQJT_B*nIAcdgHR?;k$QKIdt#6NA z_!VDSatrr_mC*_KLSB5#rkN9aJ#{_uADuhN=T%w}`pynpGH(9dv1+LsRw;em2JPCu zeI5fyD&3x9NZ$@m%D-@u0H&hu58y%E+%FuKMVuwiZj>J^lmSLYM%HD3RM7n&Mi0g< z?RHL1WXH$YR+$Q6_TNAMJcN5E={KvGwp)0n15^#0J-d8Ms}mJB8c_K=+w<3pq`%Vc_Nxpss@|ybEL|CNg+fw&=QX!4xY^Bh{4AbY` zOlt_t+4ipc_VxYobRoocTv~z}$MbDu{tw*!_mexSxDu?%V(fb+sVE#%($67l#{Gi? zx(fw0cW>r9tXfrUJ*$r>D7VNmDv?dak|g+hCZvxe+M(I?DW-AbORN=pqK3s<@#l~( z;DXEl6QYfXLFzOc#ogOsojYJ@F}z#0m9@3c+ioU$pDA+i z4jVHjr|MV)7jaZ zUw6}w@e3@R3zsh4uHC=1^6BaJMvrBY!W0Fwg5a81mWN%aO^wVyE;T%eGBFjPtH(-f z?1X7X^7>t~&-~8lKKsFrBJ9+Y=bbfJOe=EKNLwt+wY{XJsIT>9uN3yksA+kxduh8w zB6C7y1ULtOdJaRv*MG00#$aSlpU(&W?TK1)p zr%s)!+C98r54sjPIk{WW8LZI>|FcH5v~r^;y_kt?!Z^<|z?E7@S$rgTbB!}S!&d|+BuusNVmsEcs802__G4Ww!6!xqy2sEQnMCjLmV$hoE%9kD0 z{t50lOFOZ5NO)GM295{o)f7jJ$k-%vP>OTnoi(1ET7y<8#;OYBzS@cZHQ3|-Qttd8 zv!lGtpZjR=!Od^kDpI4P zmrS0%N!NQ>LUHBJ?5m|bymP}f!r$=na(6r;4m`oxp-4|o8bcZ)PYu<7?O?|@P}A~N z+cwxZCT>;htB9;ScMeLa^MY-i=eGQ7eO!9s!nhXuI3nWW~|*=Z}3JlytH_0;Ngk!|^MZ3=Tk(S~e zr@OR@ovm+fUJ>;g_NeufeCTPNJ@PE8{}1ysmqS6ydo!+GE1r3sp7VC~D3-mNihthe zN^ce97UGhU5*-s`A3rOsZ%A^g zInLS1=Z{f+_V-R!8edIrhF>gUYuq!RHDhgnRd`K^<%QZXw1HEl)WS0?BI{^ zr!@pIv)ioNL<=*lGw@2)9^0Tzllre%ySBWxo#n4`=;`>5&v=`rU+t|ZvXm;onnN)(SkVRP%s`5WWh|xG-C!}_|e+hT4$rf zQ@R)3o_$pRX>>+LM)<_;`lonDEz!qUS6Z>+T6#p!(9lRSP~?N^t6b_WomG;5^q&ln zOGUbJ($}%Hj21JJ@ZkABL<+$#V?y?H&^Q;*?SA&33cD?Wj>=Bde! zJOBUy literal 0 HcmV?d00001 diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/frontend_utils/CommonFunctions.h b/src/localization_module_lio_locus/include/lio_locus_humble/frontend_utils/CommonFunctions.h new file mode 100755 index 0000000..cbc7627 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/frontend_utils/CommonFunctions.h @@ -0,0 +1,39 @@ +#pragma once + +#include +#include +template +Eigen::Matrix PCLTwoPlaneVectorsFromNormal(const PointF& normal) { + Eigen::Matrix vec1, vec2; + Eigen::Matrix normal_eig(normal._PointXYZINormal::normal_x, + normal._PointXYZINormal::normal_y, + normal._PointXYZINormal::normal_z); + normal_eig.normalize(); + vec1[0] = 1.0; + vec1[1] = 0.0; + if (std::abs(normal._PointXYZINormal::normal_z) < 0.0000001 or + std::abs(normal_eig[2]) < 0.0000001) { + normal_eig[2] = 0.0000001; + } + vec1[2] = -normal_eig[0] / normal_eig[2]; + vec1.normalize(); + vec2 = normal_eig.cross(vec1); + vec2.normalize(); + + return 0.001 * normal_eig * normal_eig.transpose() + vec1 * vec1.transpose() + + vec2 * vec2.transpose(); +} + +template +void CalculateCovarianceFromNormals(const PointCloudF::ConstPtr& point_cloud, + MatricesVectorT& cloud_covariances, + int k_num_threads = 1) { + Eigen::Matrix vec1, vec2; + cloud_covariances.resize(point_cloud->size()); + omp_set_num_threads(k_num_threads); +#pragma omp parallel for schedule(dynamic, 1) + for (int i = 0; i < point_cloud->points.size(); ++i) { + cloud_covariances[i] = + PCLTwoPlaneVectorsFromNormal(point_cloud->points[i]); + } +} diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/frontend_utils/CommonStructs.h b/src/localization_module_lio_locus/include/lio_locus_humble/frontend_utils/CommonStructs.h new file mode 100755 index 0000000..366a0f9 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/frontend_utils/CommonStructs.h @@ -0,0 +1,28 @@ +#pragma once +//#include +#include +#include + + +#include + +typedef pcl::PointXYZINormal PointF; +typedef pcl::PointCloud PointCloudF; +typedef pcl::PointCloud::ConstPtr pclConstPtr; +typedef pcl::PointCloud::Ptr pclPtr; + +typedef std::vector> + MatricesVector; +typedef boost::shared_ptr MatricesVectorPtr; + +typedef std::vector> + MatricesVectorf; +typedef boost::shared_ptr MatricesVectorfPtr; + +template +using MatricesVectorT = + std::vector, + Eigen::aligned_allocator>>; + +template +using MatricesVectorTPtr = boost::shared_ptr>; diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtils.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtils.h new file mode 100755 index 0000000..de89132 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtils.h @@ -0,0 +1,160 @@ +/* + geometry_utils: Utility library to provide common geometry types and + transformations Copyright (C) 2014 Nathan Michael 2016 Erik Nelson + + This program is free software; you can redistribute it and/or + modify it under the terms of the GNU General Public License + as published by the Free Software Foundation; either version 2 + of the License, or (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, + USA. +*/ + +#ifndef GEOMETRY_UTILS_H +#define GEOMETRY_UTILS_H + +#include "Matrix2x2.h" +#include "Matrix3x3.h" +#include "Matrix4x4.h" +#include "Quaternion.h" +#include "Rotation2.h" +#include "Rotation3.h" +#include "Transform2.h" +#include "Transform3.h" +#include "Vector2.h" +#include "Vector3.h" +#include "Vector4.h" + +namespace geometry_utils +{ +inline double Unroll(double x) +{ + x = fmod(x, 2.0 * M_PI); + if (x < 0) + x += 2.0 * M_PI; + return x; +} + +inline double Normalize(double x) +{ + x = fmod(x + M_PI, 2.0 * M_PI); + if (x < 0) + x += 2.0 * M_PI; + return x - M_PI; +} + +inline double S1Distance(double from, double to) +{ + double result = Unroll(Unroll(to) - Unroll(from)); + if (result > M_PI) + result = -(2.0 * M_PI - result); + return Normalize(result); +} + +inline double Rad2Deg(double angle) +{ + return angle * 180.0 * M_1_PI; +} + +inline double Deg2Rad(double angle) +{ + return angle * M_PI / 180.0; +} + +inline Vec3 Rad2Deg(const Vec3& angles) +{ + return Vec3(Rad2Deg(angles(0)), Rad2Deg(angles(1)), Rad2Deg(angles(2))); +} + +inline Vec3 Deg2Rad(const Vec3& angles) +{ + return Vec3(Deg2Rad(angles(0)), Deg2Rad(angles(1)), Deg2Rad(angles(2))); +} + +inline Vec3 RToZYX(const Rot3& rot) +{ + return rot.GetEulerZYX(); +} + +inline Rot3 ZYXToR(const Vec3& angles) +{ + return Rot3(angles); +} + +inline Rot3 QuatToR(const Quat& quat) +{ + return Rot3(quat); +} + +inline Quat RToQuat(const Rot3& rot) +{ + return Quat(Eigen::Quaterniond(rot.Eigen())); +} + +inline double GetRoll(const Rot3& r) +{ + return r.Roll(); +} + +inline double GetRoll(const Quat& q) +{ + return Rot3(q).Roll(); +} + +inline double GetPitch(const Rot3& r) +{ + return r.Pitch(); +} + +inline double GetPitch(const Quat& q) +{ + return Rot3(q).Pitch(); +} + +inline double GetYaw(const Rot3& r) +{ + return r.Yaw(); +} + +inline double GetYaw(const Quat& q) +{ + return Rot3(q).Yaw(); +} + +inline double SO3Error(const Quat& q1, const Quat& q2) +{ + return Rot3(q1).Error(Rot3(q2)); +} + +inline double SO3Error(const Rot3& r1, const Rot3& r2) +{ + return r1.Error(r2); +} + +inline Vec3 CartesianToSpherical(const Vec3& v) +{ + double rho = v.Norm(); + return Vec3(rho, acos(v.Z() / rho), atan2(v.Y(), v.X())); +} + +inline Vec3 SphericalToCartesian(const Vec3& v) +{ + return Vec3(v(0) * sin(v(1)) * cos(v(2)), v(0) * sin(v(1)) * sin(v(2)), v(0) * cos(v(1))); +} + +inline Vec3 NEDCartesian(const Vec3& v) +{ + return Vec3(v(0), -v(1), -v(2)); +} + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsMath.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsMath.h new file mode 100755 index 0000000..bf5614b --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsMath.h @@ -0,0 +1,201 @@ +/* + geometry_utils: Utility library to provide common geometry types and + transformations Copyright (C) 2014 Nathan Michael 2016 Erik Nelson + + This program is free software; you can redistribute it and/or + modify it under the terms of the GNU General Public License + as published by the Free Software Foundation; either version 2 + of the License, or (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, + USA. +*/ + +#ifndef GEOMETRY_UTILS_MATH_H +#define GEOMETRY_UTILS_MATH_H + +#include + +namespace geometry_utils +{ +namespace math +{ +template +inline T cos(T in); +template <> +inline float cos(float in) +{ + return ::cosf(in); +} +template <> +inline double cos(double in) +{ + return ::cos(in); +} + +template +inline T acos(T in); +template <> +inline float acos(float in) +{ + return ::acosf(in); +} +template <> +inline double acos(double in) +{ + return ::acos(in); +} + +template +inline T sin(T in); +template <> +inline float sin(float in) +{ + return ::sinf(in); +} +template <> +inline double sin(double in) +{ + return ::sin(in); +} + +template +inline T asin(T in); +template <> +inline float asin(float in) +{ + return ::asinf(in); +} +template <> +inline double asin(double in) +{ + return ::asin(in); +} + +template +inline T tan(T in); +template <> +inline float tan(float in) +{ + return ::tanf(in); +} +template <> +inline double tan(double in) +{ + return ::tan(in); +} + +template +inline T atan(T in); +template <> +inline float atan(float in) +{ + return ::atanf(in); +} +template <> +inline double atan(double in) +{ + return ::atan(in); +} + +template +inline T fabs(T in); +template <> +inline float fabs(float in) +{ + return ::fabsf(in); +} +template <> +inline double fabs(double in) +{ + return ::fabs(in); +} + +template +inline T fmin(T v1, T v2); +template <> +inline float fmin(float v1, float v2) +{ + return ::fminf(v1, v2); +} +template <> +inline double fmin(double v1, double v2) +{ + return ::fmin(v1, v2); +} + +template +inline T fmax(T v1, T v2); +template <> +inline float fmax(float v1, float v2) +{ + return ::fmaxf(v1, v2); +} +template <> +inline double fmax(double v1, double v2) +{ + return ::fmax(v1, v2); +} + +template +inline T sqrt(T in); +template <> +inline float sqrt(float in) +{ + return ::sqrtf(in); +} +template <> +inline double sqrt(double in) +{ + return ::sqrt(in); +} + +template +inline T pow(T in, T exp); +template <> +inline float pow(float in, float exp) +{ + return ::powf(in, exp); +} +template <> +inline double pow(double in, double exp) +{ + return ::pow(in, exp); +} + +template +inline T atan2(T y, T x); +template <> +inline float atan2(float y, float x) +{ + return ::atan2f(y, x); +} +template <> +inline double atan2(double y, double x) +{ + return ::atan2(y, x); +} + +template +inline T hypot(T x, T y); +template <> +inline float hypot(float x, float y) +{ + return ::hypotf(x, y); +} +template <> +inline double hypot(double x, double y) +{ + return ::hypot(x, y); +} + +} // namespace math +} // namespace geometry_utils +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsROS.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsROS.h new file mode 100755 index 0000000..02234e2 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsROS.h @@ -0,0 +1,211 @@ +/* +geometry_utils: Utility library to provide common geometry types and +transformations Copyright (C) 2013 Nathan Michael 2015 Erik Nelson + +This program is free software; you can redistribute it and/or +modify it under the terms of the GNU General Public License +as published by the Free Software Foundation; either version 2 +of the License, or (at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. +*/ + +#ifndef GEOMETRY_UTILS_ROS_H +#define GEOMETRY_UTILS_ROS_H + +#include "GeometryUtils.h" + +#include +#include +#include +#include +#include +#include + +// check headers for ros messages; + +namespace geometry_utils +{ +namespace ros +{ + +inline void test(){ + + // geometry_msgs__msg__Point32 + +} + +inline Vec3 FromROS( const geometry_msgs::msg::Point& p) +{ + + + return Vec3(p.x, p.y, p.z); +} + +inline Vec3 FromROS(const geometry_msgs::msg::Point32& p) +{ + return Vec3(p.x, p.y, p.z); +} + +inline Vec3 FromROS(const geometry_msgs::msg::Vector3& p) +{ + return Vec3(p.x, p.y, p.z); +} + +inline Quat FromROS(const geometry_msgs::msg::Quaternion& msg) +{ + return Quat(msg.w, msg.x, msg.y, msg.z); +} + +inline Transform3 FromROS(const geometry_msgs::msg::Pose& msg) +{ + return Transform3(FromROS(msg.position), QuatToR(FromROS(msg.orientation))); +} + +inline Transform3 FromROS(const geometry_msgs::msg::Transform& msg) +{ + return Transform3(FromROS(msg.translation), QuatToR(FromROS(msg.rotation))); +} + +inline geometry_msgs::msg::Point ToRosPoint(const Vec2& v) +{ + geometry_msgs::msg::Point msg; + msg.x = v(0); + msg.y = v(1); + msg.z = 0.0; + + return msg; +} + +inline geometry_msgs::msg::Point ToRosPoint(const Vec3& v) +{ + geometry_msgs::Point msg; + msg.x = v(0); + msg.y = v(1); + msg.z = v(2); + + return msg; +} + +inline geometry_msgs::msg::Point32 ToRosPoint32(const Vec2& v) +{ + geometry_msgs::msg::Point32 msg; + msg.x = v(0); + msg.y = v(1); + msg.z = 0.0f; + + return msg; +} + +inline geometry_msgs::msg::Point32 ToRosPoint32(const Vec3& v) +{ + geometry_msgs::msg::Point32 msg; + msg.x = v(0); + msg.y = v(1); + msg.z = v(2); + + return msg; +} + +inline geometry_msgs::msg::Vector3 ToRosVec(const Vec2& v) +{ + geometry_msgs::msg::Vector3 msg; + msg.x = v(0); + msg.y = v(1); + msg.z = 0.0; + + return msg; +} + +inline geometry_msgs::msg::Vector3 ToRosVec(const Vec3& v) +{ + geometry_msgs::msg::Vector3 msg; + msg.x = v(0); + msg.y = v(1); + msg.z = v(2); + + return msg; +} + +inline geometry_msgs::msg::Quaternion ToRosQuat(const Quat& quat) +{ + geometry_msgs::msg::Quaternion msg; + msg.w = quat.W(); + msg.x = quat.X(); + msg.y = quat.Y(); + msg.z = quat.Z(); + + return msg; +} + +inline geometry_msgs::msg::Pose ToRosPose(const Transform2& trans) +{ + geometry_msgs::msg::Pose msg; + msg.position = ToRosPoint(trans.translation); + msg.orientation = ToRosQuat(RToQuat(Rot3(trans.rotation))); + + return msg; +} + +inline geometry_msgs::msg::Pose ToRosPose(const Transform3& trans) +{ + geometry_msgs::msg::Pose msg; + msg.position = ToRosPoint(trans.translation); + msg.orientation = ToRosQuat(RToQuat(trans.rotation)); + + return msg; +} + +inline geometry_msgs::msg::Transform ToRosTransform(const Transform2& trans) +{ + geometry_msgs::msg::Transform msg; + msg.translation = ToRosVec(trans.translation); + msg.rotation = ToRosQuat(RToQuat(Rot3(trans.rotation))); + + return msg; +} + +inline geometry_msgs::msg::Transform ToRosTransform(const Transform3& trans) +{ + geometry_msgs::msg::Transform msg; + msg.translation = ToRosVec(trans.translation); + msg.rotation = ToRosQuat(RToQuat(trans.rotation)); + + return msg; +} + +inline geometry_msgs::msg::Quaternion ToRosQuat(const Vec3& angles) +{ + return ToRosQuat(RToQuat(ZYXToR(angles))); +} + +inline Vec3 RosQuatToZYX(const geometry_msgs::msg::Quaternion& msg) +{ + return RToZYX(QuatToR(FromROS(msg))); +} + +inline double GetRoll(const geometry_msgs::msg::Quaternion& q) +{ + return Rot3(FromROS(q)).Roll(); +} + +inline double GetPitch(const geometry_msgs::msg::Quaternion& q) +{ + return Rot3(FromROS(q)).Pitch(); +} + +inline double GetYaw(const geometry_msgs::msg::Quaternion& q) +{ + return Rot3(FromROS(q)).Yaw(); +} + +} // namespace ros +} // namespace geometry_utils +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsSerialization.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsSerialization.h new file mode 100755 index 0000000..c18f70e --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/GeometryUtilsSerialization.h @@ -0,0 +1,73 @@ +/* +geometry_utils: Utility library to provide common geometry types and +transformations Copyright (C) 2013 Nathan Michael 2016 Erik Nelson + +This program is free software; you can redistribute it and/or +modify it under the terms of the GNU General Public License +as published by the Free Software Foundation; either version 2 +of the License, or (at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. +*/ + +#ifndef GEOMETRY_UTILS_SERIALIZATION_H +#define GEOMETRY_UTILS_SERIALIZATION_H + +#include "GeometryUtils.h" + +#include +#include + +namespace boost +{ +namespace serialization +{ +template +void Serialize(Archive& ar, geometry_utils::Vector2& v, const unsigned int version) +{ + ar& v(0); + ar& v(1); +} + +template +void Serialize(Archive& ar, geometry_utils::Vector3& v, const unsigned int version) +{ + ar& v(0); + ar& v(1); + ar& v(2); +} + +template +void Serialize(Archive& ar, geometry_utils::Vector4& v, const unsigned int version) +{ + ar& v(0); + ar& v(1); + ar& v(2); + ar& v(3); +} + +template +void Serialize(Archive& ar, geometry_utils::Matrix3x3& m, const unsigned int version) +{ + for (unsigned int i = 0; i < 3; i++) + for (unsigned int j = 0; j < 3; j++) + ar& m(i, j); +} + +template +void Serialize(Archive& ar, geometry_utils::Transform& t, const unsigned int version) +{ + ar& t.translation; + ar& t.rotation; +} + +} // namespace serialization +} // namespace boost +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix2x2.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix2x2.h new file mode 100755 index 0000000..dd85e8d --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix2x2.h @@ -0,0 +1,117 @@ +#ifndef GEOMETRY_UTILS_MATRIX2X2_H +#define GEOMETRY_UTILS_MATRIX2X2_H + +#include "MatrixNxNBase.h" +#include "Vector2.h" + +namespace geometry_utils +{ +template +struct Matrix2x2Base : MatrixNxNBase +{ + Matrix2x2Base() : MatrixNxNBase() + { + } + Matrix2x2Base(T val) : MatrixNxNBase(val) + { + } + Matrix2x2Base(const Matrix2x2Base& in) : MatrixNxNBase(in.data) + { + } + Matrix2x2Base(const boost::array& in) : MatrixNxNBase(in) + { + } + Matrix2x2Base(T (&in)[2 * 2]) : MatrixNxNBase(in) + { + } + Matrix2x2Base(const Eigen::Matrix& in) : MatrixNxNBase(in) + { + } + Matrix2x2Base(const MatrixNxNBase& in) : MatrixNxNBase(in) + { + } + Matrix2x2Base(const MatrixNxMBase& in) : MatrixNxNBase(in) + { + } + + Matrix2x2Base(T R11, T R12, T R21, T R22) + { + this->data[0] = R11; + this->data[1] = R12; + this->data[2] = R21; + this->data[3] = R22; + } + + virtual inline T Det() const + { + T a = this->data[0]; + T b = this->data[1]; + T c = this->data[2]; + T d = this->data[3]; + return (-(b * c) + a * d); + } + + virtual inline MatrixNxNBase Inv() const + { + Vector2Base e(SingularValues()); + + T emax = e(0); + T emin = e(1); + + if (emin < std::numeric_limits::denorm_min()) + throw std::runtime_error("Matrix2x2Base: appears singular"); + + if (emax / emin > std::numeric_limits::epsilon()) + { + T a = this->data[0]; + T b = this->data[1]; + T c = this->data[2]; + T d = this->data[3]; + + T tmp[4] = { d / (-b * c + a * d), b / (b * c - a * d), c / (b * c - a * d), a / (-b * c + a * d) }; + return MatrixNxNBase(tmp); + } + else + throw std::runtime_error("Matrix2x2Base: appears singular"); + } + + virtual inline Vector2Base SingularValues() const + { + T a = this->data[0]; + T b = this->data[1]; + T c = this->data[2]; + T d = this->data[3]; + + T tmp1 = a * a + b * b + c * c + d * d; + T tmp2 = math::sqrt((math::pow(b + c, static_cast(2)) + math::pow(a - d, static_cast(2))) * + (math::pow(b - c, static_cast(2)) + math::pow(a + d, static_cast(2)))); + + T e1 = math::sqrt(tmp1 - tmp2) * M_SQRT1_2; + T e2 = math::sqrt(tmp1 + tmp2) * M_SQRT1_2; + + return Vector2Base(e1 > e2 ? e1 : e2, e1 < e2 ? e1 : e2); + } +}; + +inline Matrix2x2Base operator*(const float& lhs, const Matrix2x2Base& rhs) +{ + return Matrix2x2Base(rhs * lhs); +} + +inline Matrix2x2Base operator*(const double& lhs, const Matrix2x2Base& rhs) +{ + return Matrix2x2Base(rhs * lhs); +} + +typedef Matrix2x2Base Matrix2x2f; +typedef Matrix2x2Base Mat22f; + +typedef Matrix2x2Base Matrix2x2d; +typedef Matrix2x2Base Mat22d; + +typedef Matrix2x2Base Matrix2x2; +typedef Matrix2x2Base Mat22; + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix3x3.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix3x3.h new file mode 100755 index 0000000..b14ccbf --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix3x3.h @@ -0,0 +1,111 @@ +#ifndef GEOMETRY_UTILS_MATRIX3X3_H +#define GEOMETRY_UTILS_MATRIX3X3_H + +#include "MatrixNxNBase.h" + +namespace geometry_utils +{ +template +struct Matrix3x3Base : MatrixNxNBase +{ + Matrix3x3Base() : MatrixNxNBase() + { + } + Matrix3x3Base(T val) : MatrixNxNBase(val) + { + } + Matrix3x3Base(const Matrix3x3Base& in) : MatrixNxNBase(in.data) + { + } + Matrix3x3Base(const boost::array& in) : MatrixNxNBase(in) + { + } + Matrix3x3Base(T (&in)[9]) : MatrixNxNBase(in) + { + } + Matrix3x3Base(const Eigen::Matrix& in) : MatrixNxNBase(in) + { + } + Matrix3x3Base(const MatrixNxNBase& in) : MatrixNxNBase(in) + { + } + Matrix3x3Base(const MatrixNxMBase& in) : MatrixNxNBase(in) + { + } + + Matrix3x3Base(T R11, T R12, T R13, T R21, T R22, T R23, T R31, T R32, T R33) + { + this->data[0] = R11; + this->data[1] = R12; + this->data[2] = R13; + this->data[3] = R21; + this->data[4] = R22; + this->data[5] = R23; + this->data[6] = R31; + this->data[7] = R32; + this->data[8] = R33; + } + + inline T Det() const + { + T a = this->data[0]; + T b = this->data[1]; + T c = this->data[2]; + T d = this->data[3]; + T e = this->data[4]; + T f = this->data[5]; + T g = this->data[6]; + T h = this->data[7]; + T i = this->data[8]; + return (-(c * e * g) + b * f * g + c * d * h - a * f * h - b * d * i + a * e * i); + } + + virtual inline MatrixNxNBase Inv() const + { + if (math::fabs(Det()) < std::numeric_limits::denorm_min()) + throw std::runtime_error("Matrix3x3Base: appears singular"); + + T a = this->data[0]; + T b = this->data[1]; + T c = this->data[2]; + T d = this->data[3]; + T e = this->data[4]; + T f = this->data[5]; + T g = this->data[6]; + T h = this->data[7]; + T i = this->data[8]; + T tmp[9] = { (f * h - e * i) / (c * e * g - b * f * g - c * d * h + a * f * h + b * d * i - a * e * i), + (c * h - b * i) / (-(c * e * g) + b * f * g + c * d * h - a * f * h - b * d * i + a * e * i), + (c * e - b * f) / (c * e * g - b * f * g - c * d * h + a * f * h + b * d * i - a * e * i), + (f * g - d * i) / (-(c * e * g) + b * f * g + c * d * h - a * f * h - b * d * i + a * e * i), + (c * g - a * i) / (c * e * g - b * f * g - c * d * h + a * f * h + b * d * i - a * e * i), + (c * d - a * f) / (-(c * e * g) + b * f * g + c * d * h - a * f * h - b * d * i + a * e * i), + (e * g - d * h) / (c * e * g - b * f * g - c * d * h + a * f * h + b * d * i - a * e * i), + (b * g - a * h) / (-(c * e * g) + b * f * g + c * d * h - a * f * h - b * d * i + a * e * i), + (b * d - a * e) / (c * e * g - b * f * g - c * d * h + a * f * h + b * d * i - a * e * i) }; + return MatrixNxNBase(tmp); + } +}; + +inline Matrix3x3Base operator*(const float& lhs, const Matrix3x3Base& rhs) +{ + return Matrix3x3Base(rhs.Scale(lhs)); +} + +inline Matrix3x3Base operator*(const double& lhs, const Matrix3x3Base& rhs) +{ + return Matrix3x3Base(rhs.Scale(lhs)); +} + +typedef Matrix3x3Base Matrix3x3f; +typedef Matrix3x3Base Mat33f; + +typedef Matrix3x3Base Matrix3x3d; +typedef Matrix3x3Base Mat33d; + +typedef Matrix3x3Base Matrix3x3; +typedef Matrix3x3Base Mat33; + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix4x4.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix4x4.h new file mode 100755 index 0000000..544fcec --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Matrix4x4.h @@ -0,0 +1,209 @@ +#ifndef GEOMETRY_UTILS_MATRIX4X4_H +#define GEOMETRY_UTILS_MATRIX4X4_H + +#include "MatrixNxNBase.h" + +namespace geometry_utils +{ +template +struct Matrix4x4Base : MatrixNxNBase +{ + Matrix4x4Base() : MatrixNxNBase() + { + } + Matrix4x4Base(T val) : MatrixNxNBase(val) + { + } + Matrix4x4Base(const Matrix4x4Base& in) : MatrixNxNBase(in.data) + { + } + Matrix4x4Base(const boost::array& in) : MatrixNxNBase(in) + { + } + Matrix4x4Base(T (&in)[16]) : MatrixNxNBase(in) + { + } + Matrix4x4Base(const Eigen::Matrix& in) : MatrixNxNBase(in) + { + } + Matrix4x4Base(const MatrixNxNBase& in) : MatrixNxNBase(in) + { + } + Matrix4x4Base(const MatrixNxMBase& in) : MatrixNxNBase(in) + { + } + + Matrix4x4Base(T R11, T R12, T R13, T R14, T R21, T R22, T R23, T R24, T R31, T R32, T R33, T R34, T R41, T R42, T R43, + T R44) + { + this->data[0] = R11; + this->data[1] = R12; + this->data[2] = R13; + this->data[3] = R14; + this->data[4] = R21; + this->data[5] = R22; + this->data[6] = R23; + this->data[7] = R24; + this->data[8] = R31; + this->data[9] = R32; + this->data[10] = R33; + this->data[11] = R34; + this->data[12] = R41; + this->data[13] = R42; + this->data[14] = R43; + this->data[15] = R44; + } + + inline T Det() const + { + T a = this->data[0]; + T b = this->data[1]; + T c = this->data[2]; + T d = this->data[3]; + T e = this->data[4]; + T f = this->data[5]; + T g = this->data[6]; + T h = this->data[7]; + T i = this->data[8]; + T j = this->data[9]; + T k = this->data[10]; + T l = this->data[11]; + T m = this->data[12]; + T n = this->data[13]; + T o = this->data[14]; + T p = this->data[15]; + + return d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p; + } + + virtual inline MatrixNxNBase Inv() const + { + if (math::fabs(Det()) < std::numeric_limits::denorm_min()) + throw std::runtime_error("Matrix4x4Base: appears singular"); + + T a = this->data[0]; + T b = this->data[1]; + T c = this->data[2]; + T d = this->data[3]; + T e = this->data[4]; + T f = this->data[5]; + T g = this->data[6]; + T h = this->data[7]; + T i = this->data[8]; + T j = this->data[9]; + T k = this->data[10]; + T l = this->data[11]; + T m = this->data[12]; + T n = this->data[13]; + T o = this->data[14]; + T p = this->data[15]; + + T tmp[16] = { (-(h * k * n) + g * l * n + h * j * o - f * l * o - g * j * p + f * k * p) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (d * k * n - c * l * n - d * j * o + b * l * o + c * j * p - b * k * p) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (-(d * g * n) + c * h * n + d * f * o - b * h * o - c * f * p + b * g * p) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (d * g * j - c * h * j - d * f * k + b * h * k + c * f * l - b * g * l) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (h * k * m - g * l * m - h * i * o + e * l * o + g * i * p - e * k * p) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (-(d * k * m) + c * l * m + d * i * o - a * l * o - c * i * p + a * k * p) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (d * g * m - c * h * m - d * e * o + a * h * o + c * e * p - a * g * p) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (-(d * g * i) + c * h * i + d * e * k - a * h * k - c * e * l + a * g * l) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (-(h * j * m) + f * l * m + h * i * n - e * l * n - f * i * p + e * j * p) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (d * j * m - b * l * m - d * i * n + a * l * n + b * i * p - a * j * p) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (-(d * f * m) + b * h * m + d * e * n - a * h * n - b * e * p + a * f * p) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (d * f * i - b * h * i - d * e * j + a * h * j + b * e * l - a * f * l) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (g * j * m - f * k * m - g * i * n + e * k * n + f * i * o - e * j * o) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (-(c * j * m) + b * k * m + c * i * n - a * k * n - b * i * o + a * j * o) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (c * f * m - b * g * m - c * e * n + a * g * n + b * e * o - a * f * o) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p), + (-(c * f * i) + b * g * i + c * e * j - a * g * j - b * e * k + a * f * k) / + (d * g * j * m - c * h * j * m - d * f * k * m + b * h * k * m + c * f * l * m - b * g * l * m - + d * g * i * n + c * h * i * n + d * e * k * n - a * h * k * n - c * e * l * n + a * g * l * n + + d * f * i * o - b * h * i * o - d * e * j * o + a * h * j * o + b * e * l * o - a * f * l * o - + c * f * i * p + b * g * i * p + c * e * j * p - a * g * j * p - b * e * k * p + a * f * k * p) }; + return MatrixNxNBase(tmp); + } +}; + +inline Matrix4x4Base operator*(const float& lhs, const Matrix4x4Base& rhs) +{ + return Matrix4x4Base(rhs.Scale(lhs)); +} + +inline Matrix4x4Base operator*(const double& lhs, const Matrix4x4Base& rhs) +{ + return Matrix4x4Base(rhs.Scale(lhs)); +} + +typedef Matrix4x4Base Matrix4x4f; +typedef Matrix4x4Base Mat44f; + +typedef Matrix4x4Base Matrix4x4d; +typedef Matrix4x4Base Mat44d; + +typedef Matrix4x4Base Matrix4x4; +typedef Matrix4x4Base Mat44; + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/MatrixNxMBase.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/MatrixNxMBase.h new file mode 100755 index 0000000..c73fc6b --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/MatrixNxMBase.h @@ -0,0 +1,335 @@ +#ifndef GEOMETRY_UTILS_MATRIXNXM_H +#define GEOMETRY_UTILS_MATRIXNXM_H + +#include "GeometryUtilsMath.h" +#include "VectorNBase.h" +#include + +namespace geometry_utils +{ +template +struct MatrixNxMBase +{ + typedef typename boost::shared_ptr> Ptr; + typedef typename boost::shared_ptr> ConstPtr; + + static const size_t size = N * M; + static const size_t nrows = N; + static const size_t ncols = M; + + boost::array data; + + MatrixNxMBase() + { + data.fill(0); + } + + MatrixNxMBase(T val) + { + data.fill(val); + } + + MatrixNxMBase(const MatrixNxMBase& in) : data(in.data) + { + } + + MatrixNxMBase(const boost::array& in) : data(in) + { + } + + MatrixNxMBase(T (&in)[size]) + { + for (unsigned int i = 0; i < size; i++) + data[i] = in[i]; + } + + MatrixNxMBase(const Eigen::Matrix& in) + { + for (size_t i = 0; i < nrows; i++) + for (size_t j = 0; j < ncols; j++) + data[ncols * i + j] = in(i, j); + } + + inline T& operator()(unsigned int i) + { + return data[i]; + } + + inline const T& operator()(unsigned int i) const + { + return data[i]; + } + + inline T& Get(unsigned int i) + { + return data[i]; + } + + inline const T& Get(unsigned int i) const + { + return data[i]; + } + + inline T& operator()(unsigned int i, unsigned int j) + { + return data[ncols * i + j]; + } + + inline const T& operator()(unsigned int i, unsigned int j) const + { + return data[ncols * i + j]; + } + + inline T& Get(unsigned int i, unsigned int j) + { + return data[ncols * i + j]; + } + + inline const T& Get(unsigned int i, unsigned int j) const + { + return data[ncols * i + j]; + } + + inline std::ostream& operator<<(std::ostream& out) + { + out << data; + return out; + } + + inline MatrixNxMBase& operator=(const MatrixNxMBase& rhs) + { + if (this == &rhs) + return *this; + data = rhs.data; + return *this; + } + + inline MatrixNxMBase operator*(T rhs) const + { + T d[size]; + for (size_t i = 0; i < size; i++) + d[i] = data[i] * rhs; + return MatrixNxMBase(d); + } + + inline MatrixNxMBase operator+(const MatrixNxMBase& rhs) const + { + T d[size]; + for (size_t i = 0; i < size; i++) + d[i] = data[i] + rhs(i); + return MatrixNxMBase(d); + } + + inline MatrixNxMBase operator-() const + { + T d[size]; + for (size_t i = 0; i < size; i++) + d[i] = -data[i]; + return MatrixNxMBase(d); + } + + inline MatrixNxMBase operator-(const MatrixNxMBase& rhs) const + { + T d[size]; + for (size_t i = 0; i < size; i++) + d[i] = data[i] - rhs(i); + return MatrixNxMBase(d); + } + + inline MatrixNxMBase operator*(const MatrixNxMBase& rhs) const + { + T d[N * N]; + for (size_t i = 0; i < N; i++) + for (size_t j = 0; j < N; j++) + d[N * i + j] = this->Row(i) ^ rhs.Col(j); + return MatrixNxMBase(d); + } + + inline VectorNBase operator*(const VectorNBase& rhs) const + { + T d[nrows]; + for (size_t i = 0; i < nrows; i++) + d[i] = this->Row(i) ^ rhs; + return VectorNBase(d); + } + + inline MatrixNxMBase operator%(const MatrixNxMBase& rhs) const + { + T d[size]; + for (size_t i = 0; i < size; i++) + d[i] = data[i] * rhs(i); + return MatrixNxMBase(d); + } + + inline MatrixNxMBase operator/(const MatrixNxMBase& rhs) const + { + T d[size]; + for (size_t i = 0; i < size; i++) + d[i] = data[i] / rhs(i); + return MatrixNxMBase(d); + } + + inline MatrixNxMBase operator+=(const MatrixNxMBase& rhs) + { + for (size_t i = 0; i < size; i++) + data[i] += rhs.data[i]; + return *this; + } + + inline MatrixNxMBase operator-=(const MatrixNxMBase& rhs) + { + for (size_t i = 0; i < size; i++) + data[i] -= rhs.data[i]; + return *this; + } + + inline MatrixNxMBase operator%=(const MatrixNxMBase& rhs) + { + for (size_t i = 0; i < size; i++) + data[i] *= rhs.data[i]; + return *this; + } + + inline MatrixNxMBase operator/=(const MatrixNxMBase& rhs) + { + for (size_t i = 0; i < size; i++) + data[i] /= rhs.data[i]; + return *this; + } + + inline MatrixNxMBase Trans() const + { + T d[size]; + for (size_t i = 0; i < nrows; i++) + for (size_t j = 0; j < ncols; j++) + d[nrows * j + i] = data[ncols * i + j]; + return MatrixNxMBase(d); + } + + inline MatrixNxMBase t() const + { + return this->Trans(); + } + + inline VectorNBase Row(unsigned int r) const + { + T d[ncols]; + for (size_t i = 0; i < ncols; i++) + d[i] = data[ncols * r + i]; + return VectorNBase(d); + } + + inline VectorNBase Col(unsigned int c) const + { + T d[nrows]; + for (size_t i = 0; i < nrows; i++) + d[i] = data[ncols * i + c]; + return VectorNBase(d); + } + + inline void Ones() + { + data.fill(1); + } + + inline void Zeros() + { + data.fill(0); + } + + inline MatrixNxMBase Scale(T s) const + { + return (*this) * s; + } + + inline void Print(const std::string& prefix = std::string()) const + { + if (!prefix.empty()) + std::cout << prefix << std::endl; + std::cout << (*this) << std::endl; + } + + inline Eigen::Matrix Eigen() const + { + return Eigen::Matrix(data.data()).transpose(); + } + + inline bool operator==(const MatrixNxMBase& that) const + { + return this->Equals(that); + } + + inline bool operator!=(const MatrixNxMBase& that) const + { + return !this->Equals(that); + } + + virtual inline bool Equals(const MatrixNxMBase& that, const T ptol = 1e-8) const + { + return (*this - that).Norm() < ptol; + } + + inline T Norm() const + { + return math::sqrt((this->Trans() * (*this)).Trace()); + } + + inline T Trace() + { + size_t count = nrows <= ncols ? nrows : ncols; + T tr = 0; + for (size_t i = 0; i < count; i++) + tr += data[ncols * i + i]; + return tr; + } +}; + +template +inline MatrixNxMBase operator*(const float& lhs, const MatrixNxMBase& rhs) +{ + return rhs * lhs; +} + +template +inline MatrixNxMBase operator*(const double& lhs, const MatrixNxMBase& rhs) +{ + return rhs * lhs; +} + +template +inline std::ostream& operator<<(std::ostream& out, const MatrixNxMBase& m) +{ + for (size_t i = 0; i < N; i++) + { + for (size_t j = 0; j < M; j++) + out << m.data[M * i + j] << " "; + out << std::endl; + } + return out; +} + +template +inline Eigen::Matrix Eigen(const MatrixNxMBase& in) +{ + return in.Eigen(); +} + +template +inline MatrixNxMBase Trans(const MatrixNxMBase& m) +{ + return m.Trans(); +} + +template +inline MatrixNxMBase Outer(const VectorNBase& v1, const VectorNBase& v2) +{ + T d[N * M]; + for (size_t i = 0; i < N; i++) + for (size_t j = 0; j < M; j++) + d[M * i + j] = v1(i) * v2(j); + return MatrixNxMBase(d); +} + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/MatrixNxNBase.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/MatrixNxNBase.h new file mode 100755 index 0000000..239db02 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/MatrixNxNBase.h @@ -0,0 +1,84 @@ +#ifndef GEOMETRY_UTILS_MATRIXNXN_H +#define GEOMETRY_UTILS_MATRIXNXN_H + +#include "GeometryUtilsMath.h" +#include "MatrixNxMBase.h" +#include "VectorNBase.h" +#include + +namespace geometry_utils +{ +template +struct MatrixNxNBase : MatrixNxMBase +{ + MatrixNxNBase() : MatrixNxMBase() + { + } + MatrixNxNBase(T val) : MatrixNxMBase(val) + { + } + MatrixNxNBase(const MatrixNxNBase& in) : MatrixNxMBase(in.data) + { + } + MatrixNxNBase(const boost::array& in) : MatrixNxMBase(in) + { + } + MatrixNxNBase(T (&in)[N * N]) : MatrixNxMBase(in) + { + } + MatrixNxNBase(const Eigen::Matrix& in) : MatrixNxMBase(in) + { + } + MatrixNxNBase(const MatrixNxMBase& in) : MatrixNxMBase(in) + { + } + + inline void Eye() + { + this->data.fill(0); + for (size_t i = 0; i < this->nrows; i++) + this->data[this->nrows * i + i] = 1; + } + + virtual inline T Det() const + { + std::cerr << "MatrixNxMBase::det not implemented" << std::endl; + return T(); + } + + virtual inline MatrixNxNBase Inv() const + { + std::cerr << "MatrixNxMBase::inv not implemented" << std::endl; + return MatrixNxNBase(); + } + + static inline MatrixNxNBase Diag(const VectorNBase& in) + { + T d[N * N] = { 0 }; + for (size_t i = 0; i < N; i++) + d[N * i + i] = in(i); + return MatrixNxNBase(d); + } +}; + +template +inline MatrixNxNBase operator*(const float& lhs, const MatrixNxNBase& rhs) +{ + return MatrixNxNBase(rhs * lhs); +} + +template +inline MatrixNxNBase operator*(const double& lhs, const MatrixNxNBase& rhs) +{ + return MatrixNxNBase(rhs * lhs); +} + +template +inline MatrixNxNBase Inv(const MatrixNxNBase& m) +{ + return m.Inv(); +} + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Quaternion.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Quaternion.h new file mode 100755 index 0000000..377a5fe --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Quaternion.h @@ -0,0 +1,134 @@ +#ifndef GEOMETRY_UTILS_QUATERNION_H +#define GEOMETRY_UTILS_QUATERNION_H + +#include "GeometryUtilsMath.h" +#include +#include +#include + +namespace geometry_utils +{ +template +struct QuaternionBase : VectorNBase +{ + QuaternionBase() : VectorNBase() + { + this->data.assign(0); + this->data[0] = 1; + } + + QuaternionBase(T val) : VectorNBase(val) + { + } + QuaternionBase(const QuaternionBase& in) : VectorNBase(in.data) + { + } + QuaternionBase(const boost::array& in) : VectorNBase(in) + { + } + QuaternionBase(T (&in)[4]) : VectorNBase(in) + { + } + QuaternionBase(const Eigen::Quaternion& in) + { + this->data[0] = in.w(); + this->data[1] = in.x(); + this->data[2] = in.y(); + this->data[3] = in.z(); + } + QuaternionBase(const VectorNBase& in) : VectorNBase(in) + { + } + + QuaternionBase(T w, T x, T y, T z) + { + this->data[0] = w; + this->data[1] = x; + this->data[2] = y; + this->data[3] = z; + } + + inline QuaternionBase operator*(const QuaternionBase& rhs) const + { + T a1 = this->data[0]; + T b1 = this->data[1]; + T c1 = this->data[2]; + T d1 = this->data[3]; + T a2 = rhs.data[0]; + T b2 = rhs.data[1]; + T c2 = rhs.data[2]; + T d2 = rhs.data[3]; + return QuaternionBase(a1 * a2 - b1 * b2 - c1 * c2 - d1 * d2, a2 * b1 + a1 * b2 - c2 * d1 + c1 * d2, + a2 * c1 + a1 * c2 + b2 * d1 - b1 * d2, -(b2 * c1) + b1 * c2 + a2 * d1 + a1 * d2); + } + + inline T& W() + { + return this->data[0]; + } + inline const T& W() const + { + return this->data[0]; + } + + inline T& X() + { + return this->data[1]; + } + inline const T& X() const + { + return this->data[1]; + } + + inline T& Y() + { + return this->data[2]; + } + inline const T& Y() const + { + return this->data[2]; + } + + inline T& Z() + { + return this->data[3]; + } + inline const T& Z() const + { + return this->data[3]; + } + + inline QuaternionBase Conj() const + { + return QuaternionBase(this->data[0], -this->data[1], -this->data[2], -this->data[3]); + } + + inline QuaternionBase Error(const QuaternionBase& q) const + { + return q * (*this).Conj(); + } + + inline QuaternionBase AxisAngle() const + { + QuaternionBase q((*this)); + if (q.W() > 1) + q = q.Normalize(); + T den = math::sqrt(1 - q.W() * q.W()); + if (den < 1e-6) + den = 1; + return QuaternionBase(2 * math::acos(q.W()), q.X() / den, q.Y() / den, q.Z() / den); + } +}; + +typedef QuaternionBase Quaternionf; +typedef QuaternionBase Quatf; + +typedef QuaternionBase Quaterniond; +typedef QuaternionBase Quatd; + +typedef QuaternionBase Quaternion; +typedef QuaternionBase Quat; + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Rotation2.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Rotation2.h new file mode 100755 index 0000000..f64162b --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Rotation2.h @@ -0,0 +1,111 @@ +#ifndef GEOMETRY_UTILS_ROTATION2_H +#define GEOMETRY_UTILS_ROTATION2_H + +#include "GeometryUtilsMath.h" +#include "Matrix2x2.h" +#include "RotationNBase.h" +#include + +namespace geometry_utils +{ +template +struct Rotation2Base : RotationNBase +{ + Rotation2Base() : RotationNBase() + { + } + Rotation2Base(const Rotation2Base& in) : RotationNBase(in.data) + { + } + Rotation2Base(const boost::array& in) : RotationNBase(in) + { + } + Rotation2Base(T (&in)[2 * 2]) : RotationNBase(in) + { + } + Rotation2Base(const Eigen::Matrix& in) : RotationNBase(in) + { + } + Rotation2Base(const Eigen::Rotation2D& in) : RotationNBase(in.toRotationMatrix()) + { + } + Rotation2Base(const RotationNBase& in) : RotationNBase(in) + { + } + Rotation2Base(const Matrix2x2Base& in) : RotationNBase(in) + { + } + Rotation2Base(const MatrixNxMBase& in) : RotationNBase(in) + { + } + + Rotation2Base(T val) + { + FromAngle(val); + } + + Rotation2Base(T R11, T R12, T R21, T R22) + { + this->data[0] = R11; + this->data[1] = R12; + this->data[2] = R21; + this->data[3] = R22; + } + + virtual inline bool Equals(const Rotation2Base& that, const T ptol = 1e-8) const + { + return Error(that) < ptol; + } + + inline T Error(const Rotation2Base& r) const + { + return math::sin(Angle() - r.Angle()); + } + + inline T Angle() const + { + return math::atan2(this->data[2], this->data[0]); + } + + inline void FromAngle(T val) + { + this->data[0] = math::cos(val); + this->data[1] = -math::sin(val); + this->data[2] = math::sin(val); + this->data[3] = math::cos(val); + } + + inline Eigen::Rotation2D Eigen() + { + return Eigen::Rotation2D(Angle()); + } +}; + +inline Rotation2Base operator*(const float& lhs, const Rotation2Base& rhs) +{ + return Rotation2Base(rhs.Scale(lhs)); +} + +inline Rotation2Base operator*(const double& lhs, const Rotation2Base& rhs) +{ + return Rotation2Base(rhs.Scale(lhs)); +} + +template +inline Eigen::Rotation2D Eigen(const Rotation2Base& in) +{ + return in.Eigen(); +} + +typedef Rotation2Base Rotation2f; +typedef Rotation2Base Rot2f; + +typedef Rotation2Base Rotation2d; +typedef Rotation2Base Rot2d; + +typedef Rotation2Base Rotation2; +typedef Rotation2Base Rot2; + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Rotation3.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Rotation3.h new file mode 100755 index 0000000..1cf18f6 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Rotation3.h @@ -0,0 +1,223 @@ +#ifndef GEOMETRY_UTILS_ROTATION3_H +#define GEOMETRY_UTILS_ROTATION3_H + +#include "GeometryUtilsMath.h" +#include "Matrix2x2.h" +#include "Quaternion.h" +#include "Rotation2.h" +#include "RotationNBase.h" +#include "Vector3.h" +#include + +namespace geometry_utils +{ +template +struct Rotation3Base : RotationNBase +{ + Rotation3Base() : RotationNBase() + { + } + Rotation3Base(const Rotation3Base& in) : RotationNBase(in.data) + { + } + Rotation3Base(const boost::array& in) : RotationNBase(in) + { + } + Rotation3Base(T (&in)[9]) : RotationNBase(in) + { + } + Rotation3Base(const Eigen::Matrix& in) : RotationNBase(in) + { + } + Rotation3Base(const Eigen::AngleAxis& in) : RotationNBase(in.toRotationMatrix()) + { + } + Rotation3Base(const RotationNBase& in) : RotationNBase(in) + { + } + Rotation3Base(const Matrix2x2Base& in) : RotationNBase(in) + { + } + Rotation3Base(const MatrixNxMBase& in) : RotationNBase(in) + { + } + + Rotation3Base(T R11, T R12, T R13, T R21, T R22, T R23, T R31, T R32, T R33) + { + this->data[0] = R11; + this->data[1] = R12; + this->data[2] = R13; + this->data[3] = R21; + this->data[4] = R22; + this->data[5] = R23; + this->data[6] = R31; + this->data[7] = R32; + this->data[8] = R33; + } + + Rotation3Base(const Vector3Base& in) + { + FromEulerZYX(in(0), in(1), in(2)); + } + + Rotation3Base(T euler_x, T euler_y, T euler_z) + { + FromEulerZYX(euler_x, euler_y, euler_z); + } + + Rotation3Base(const Rotation2Base& rot) + { + this->Zeros(); + this->data[0] = rot(0); + this->data[1] = rot(1); + this->data[3] = rot(2); + this->data[4] = rot(3); + this->data[8] = static_cast(1); + } + + Rotation3Base(const QuaternionBase& quat) + { + QuaternionBase q(quat); + if (math::fabs(1 - q.Norm()) > static_cast(1e-6)) + q = q.Normalize(); + + T a = q.W(); + T b = q.X(); + T c = q.Y(); + T d = q.Z(); + + T a2 = a * a; + T b2 = b * b; + T c2 = c * c; + T d2 = d * d; + + T ab = a * b; + T ac = a * c; + T ad = a * d; + + T bc = b * c; + T bd = b * d; + + T cd = c * d; + + (*this)(0, 0) = a2 + b2 - c2 - d2; + (*this)(0, 1) = static_cast(2) * (bc - ad); + (*this)(0, 2) = static_cast(2) * (bd + ac); + (*this)(1, 0) = static_cast(2) * (bc + ad); + (*this)(1, 1) = a2 - b2 + c2 - d2; + (*this)(1, 2) = static_cast(2) * (cd - ab); + (*this)(2, 0) = static_cast(2) * (bd - ac); + (*this)(2, 1) = static_cast(2) * (cd + ab); + (*this)(2, 2) = a2 - b2 - c2 + d2; + } + + virtual inline bool Equals(const Rotation3Base& that, const T ptol = 1e-8) const + { + return Error(that) < ptol; + } + + inline T Error(const Rotation3Base& r) const + { + return Norm(static_cast(0.5) * Rotation3Base(this->Trans() * r - r.Trans() * (*this)).Vee()); + } + + inline Vector3Base Vee() const + { + return Vector3Base((*this)(2, 1), (*this)(0, 2), (*this)(1, 0)); + } + + inline void FromEulerZYX(T euler_x, T euler_y, T euler_z) + { + T cph = math::cos(euler_x); + T sph = math::sin(euler_x); + + T ct = math::cos(euler_y); + T st = math::sin(euler_y); + + T cps = math::cos(euler_z); + T sps = math::sin(euler_z); + + (*this)(0, 0) = ct * cps; + (*this)(0, 1) = cps * st * sph - cph * sps; + (*this)(0, 2) = cph * cps * st + sph * sps; + + (*this)(1, 0) = ct * sps; + (*this)(1, 1) = cph * cps + st * sph * sps; + (*this)(1, 2) = -cps * sph + cph * st * sps; + + (*this)(2, 0) = -st; + (*this)(2, 1) = ct * sph; + (*this)(2, 2) = ct * cph; + } + + inline Vector3Base GetEulerZYX() const + { + return ToEulerZYX(); + } + + inline Vector3Base ToEulerZYX() const + { + T theta = -math::asin((*this)(2, 0)); + T phi = 0; + T psi = 0; + if (math::fabs(cos(theta)) > static_cast(1e-6)) + { + phi = math::atan2((*this)(2, 1), (*this)(2, 2)); + psi = math::atan2((*this)(1, 0), (*this)(0, 0)); + } + + return Vector3Base(phi, theta, psi); + } + + inline T Roll() const + { + T theta = -math::asin((*this)(2, 0)); + return math::fabs(cos(theta)) > static_cast(1e-6) ? math::atan2((*this)(2, 1), (*this)(2, 2)) : 0; + } + + inline T Pitch() const + { + return -math::asin((*this)(2, 0)); + } + + inline T Yaw() const + { + T theta = -math::asin((*this)(2, 0)); + return math::fabs(cos(theta)) > static_cast(1e-6) ? math::atan2((*this)(1, 0), (*this)(0, 0)) : 0; + } +}; + +inline Rotation3Base operator*(const float& lhs, const Rotation3Base& rhs) +{ + return Rotation3Base(rhs.Scale(lhs)); +} + +inline Rotation3Base operator*(const double& lhs, const Rotation3Base& rhs) +{ + return Rotation3Base(rhs.Scale(lhs)); +} + +template +inline Rotation3Base Hat(const Vector3Base& v) +{ + return Rotation3Base(0, -v(2), v(1), v(2), 0, -v(0), -v(1), v(0), 0); +} + +template +inline Vector3Base Vee(const MatrixNxMBase& m) +{ + return Rotation3Base(m).Vee(); +} + +typedef Rotation3Base Rotation3f; +typedef Rotation3Base Rot3f; + +typedef Rotation3Base Rotation3d; +typedef Rotation3Base Rot3d; + +typedef Rotation3Base Rotation3; +typedef Rotation3Base Rot3; + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/RotationNBase.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/RotationNBase.h new file mode 100755 index 0000000..818c419 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/RotationNBase.h @@ -0,0 +1,61 @@ +#ifndef GEOMETRY_UTILS_ROTATIONN_H +#define GEOMETRY_UTILS_ROTATIONN_H + +#include "MatrixNxNBase.h" +#include "VectorNBase.h" +#include +#include + +namespace geometry_utils +{ +template +struct RotationNBase : MatrixNxNBase +{ + RotationNBase() : MatrixNxNBase() + { + this->Eye(); + } + + RotationNBase(const RotationNBase& in) : MatrixNxNBase(in.data) + { + } + RotationNBase(const boost::array& in) : MatrixNxNBase(in) + { + } + RotationNBase(T (&in)[N * N]) : MatrixNxNBase(in) + { + } + RotationNBase(const Eigen::Matrix& in) : MatrixNxNBase(in) + { + } + RotationNBase(const MatrixNxNBase& in) : MatrixNxNBase(in) + { + } + + virtual inline MatrixNxNBase Inv() const + { + return this->Trans(); + } +}; + +template +inline RotationNBase operator*(const float& lhs, const RotationNBase& rhs) +{ + return RotationNBase(rhs * lhs); +} + +template +inline RotationNBase operator*(const double& lhs, const RotationNBase& rhs) +{ + return RotationNBase(rhs * lhs); +} + +template +inline RotationNBase Inv(const RotationNBase& m) +{ + return m.Inv(); +} + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Transform2.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Transform2.h new file mode 100755 index 0000000..09aa273 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Transform2.h @@ -0,0 +1,117 @@ +#ifndef GEOMETRY_UTILS_TRANSFORM2_H +#define GEOMETRY_UTILS_TRANSFORM2_H + +#include "Rotation2.h" +#include "Vector2.h" + +namespace geometry_utils +{ +template +struct Transform2Base +{ + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + Vector2Base translation; + Rotation2Base rotation; + + Transform2Base() + { + translation.Zeros(); + rotation.Eye(); + } + + Transform2Base(const Vector2Base& translation_, const Rotation2Base& rotation_) + : translation(translation_), rotation(rotation_) + { + } + + Transform2Base(const Transform2Base& in) : translation(in.translation), rotation(in.rotation) + { + } + + Transform2Base(T x, T y, T th) : translation(x, y), rotation(th) + { + } + + Transform2Base& operator=(const Transform2Base& rhs) + { + if (this == &rhs) + return *this; + translation = rhs.translation; + rotation = rhs.rotation; + return *this; + } + + Vector2Base operator*(const Vector2Base& p) const + { + return rotation * p + translation; + } + + Transform2Base operator+(const Transform2Base& t) const + { + return Transform2Base(translation + rotation * t.translation, rotation * t.rotation); + } + + bool operator==(const Transform2Base& that) const + { + return this->Equals(that); + } + + bool operator!=(const Transform2Base& that) const + { + return !this->Equals(that); + } + + bool Equals(const Transform2Base& that, const T ptol = 1e-5, const T rtol = 1e-5) const + { + return (translation.Equals(that.translation, ptol) && rotation.Equals(that.rotation, rtol)); + } + + void Print(const std::string& prefix = std::string()) const + { + if (!prefix.empty()) + std::cout << prefix << std::endl; + std::cout << (*this) << std::endl; + } + + static Transform2Base Identity() + { + return Transform2Base(); + } +}; + +template +std::ostream& operator<<(std::ostream& out, const Transform2Base& m) +{ + out << "Translation:" << std::endl << m.translation << std::endl; + out << "Rotation:" << std::endl << m.rotation; + return out; +} + +template +Transform2Base PoseUpdate(const Transform2Base& t1, const Transform2Base& t2) +{ + return Transform2Base(t1.translation + t1.rotation * t2.translation, t1.rotation * t2.rotation); +} + +template +Transform2Base PoseInverse(const Transform2Base& t) +{ + return Transform2Base(-1.0 * t.rotation.Trans() * t.translation, t.rotation.Trans()); +} + +template +Transform2Base PoseDelta(const Transform2Base& t1, const Transform2Base& t2) +{ + return Transform2Base(t1.rotation.Trans() * (t2.translation - t1.translation), t1.rotation.Trans() * t2.rotation); +} + +typedef Transform2Base Transform2f; +typedef Transform2Base Transform2d; +typedef Transform2d Transform2; +typedef Transform2 Tr2; + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Transform3.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Transform3.h new file mode 100755 index 0000000..32ae06f --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Transform3.h @@ -0,0 +1,125 @@ +#ifndef GEOMETRY_UTILS_TRANSFORM3_H +#define GEOMETRY_UTILS_TRANSFORM3_H + +#include "Rotation3.h" +#include "Transform2.h" +#include "Vector3.h" + +namespace geometry_utils +{ +template +struct Transform3Base +{ + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + Vector3Base translation; + Rotation3Base rotation; + + Transform3Base() + { + translation.Zeros(); + rotation.Eye(); + } + + Transform3Base(const Vector3Base& translation_, const Rotation3Base& rotation_) + : translation(translation_), rotation(rotation_) + { + } + + Transform3Base(const Transform3Base& in) : translation(in.translation), rotation(in.rotation) + { + } + + Transform3Base(const Transform2Base& in) + { + translation(0) = in.translation(0); + translation(1) = in.translation(1); + translation(2) = 0; + rotation.Eye(); + for (unsigned int i = 0; i < 2; i++) + for (unsigned int j = 0; j < 2; j++) + rotation(i, j) = in.Rotation(i, j); + } + + Transform3Base& operator=(const Transform3Base& rhs) + { + if (this == &rhs) + return *this; + translation = rhs.translation; + rotation = rhs.rotation; + return *this; + } + + Vector3Base operator*(const Vector3Base& p) const + { + return rotation * p + translation; + } + + Transform3Base operator+(const Transform3Base& t) const + { + return Transform3Base(translation + rotation * t.translation, rotation * t.rotation); + } + + bool operator==(const Transform3Base& that) const + { + return this->Equals(that); + } + + bool operator!=(const Transform3Base& that) const + { + return !this->Equals(that); + } + + bool Equals(const Transform3Base& that, const T ptol = 1e-5, const T rtol = 1e-5) const + { + return (translation.Equals(that.translation, ptol) && rotation.Equals(that.rotation, rtol)); + } + + void Print(const std::string& prefix = std::string()) const + { + if (!prefix.empty()) + std::cout << prefix << std::endl; + std::cout << (*this) << std::endl; + } + + static Transform3Base Identity() + { + return Transform3Base(); + } +}; + +template +std::ostream& operator<<(std::ostream& out, const Transform3Base& m) +{ + out << "Translation:" << std::endl << m.translation << std::endl; + out << "Rotation:" << std::endl << m.rotation; + return out; +} + +template +Transform3Base PoseUpdate(const Transform3Base& t1, const Transform3Base& t2) +{ + return Transform3Base(t1.translation + t1.rotation * t2.translation, t1.rotation * t2.rotation); +} + +template +Transform3Base PoseInverse(const Transform3Base& t) +{ + return Transform3Base(-1.0 * t.rotation.Trans() * t.translation, t.rotation.Trans()); +} + +template +Transform3Base PoseDelta(const Transform3Base& t1, const Transform3Base& t2) +{ + return Transform3Base(t1.rotation.Trans() * (t2.translation - t1.translation), t1.rotation.Trans() * t2.rotation); +} + +typedef Transform3Base Transform3f; +typedef Transform3Base Transform3d; +typedef Transform3d Transform3; +typedef Transform3 Tr3; + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector2.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector2.h new file mode 100755 index 0000000..39706c2 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector2.h @@ -0,0 +1,70 @@ +#ifndef GEOMETRY_UTILS_VECTOR2_H +#define GEOMETRY_UTILS_VECTOR2_H + +#include "VectorNBase.h" + +namespace geometry_utils +{ +template +struct Vector2Base : VectorNBase +{ + Vector2Base() : VectorNBase() + { + } + Vector2Base(T val) : VectorNBase(val) + { + } + Vector2Base(const Vector2Base& in) : VectorNBase(in.data) + { + } + Vector2Base(const boost::array& in) : VectorNBase(in) + { + } + Vector2Base(T (&in)[2]) : VectorNBase(in) + { + } + Vector2Base(const Eigen::Matrix& in) : VectorNBase(in) + { + } + Vector2Base(const VectorNBase& in) : VectorNBase(in) + { + } + + Vector2Base(T v1, T v2) + { + this->data[0] = v1; + this->data[1] = v2; + } + + T X() const + { + return this->data[0]; + } + T Y() const + { + return this->data[1]; + } +}; + +inline Vector2Base operator*(const float& lhs, const Vector2Base& rhs) +{ + return Vector2Base(rhs * lhs); +} + +inline Vector2Base operator*(const double& lhs, const Vector2Base& rhs) +{ + return Vector2Base(rhs * lhs); +} + +typedef Vector2Base Vector2f; +typedef Vector2Base Vec2f; + +typedef Vector2Base Vector2d; +typedef Vector2Base Vec2d; + +typedef Vector2Base Vector2; +typedef Vector2Base Vec2; + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector3.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector3.h new file mode 100755 index 0000000..8020f99 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector3.h @@ -0,0 +1,87 @@ +#ifndef GEOMETRY_UTILS_VECTOR3_H +#define GEOMETRY_UTILS_VECTOR3_H + +#include "VectorNBase.h" + +namespace geometry_utils +{ +template +struct Vector3Base : VectorNBase +{ + Vector3Base() : VectorNBase() + { + } + Vector3Base(T val) : VectorNBase(val) + { + } + Vector3Base(const Vector3Base& in) : VectorNBase(in.data) + { + } + Vector3Base(const boost::array& in) : VectorNBase(in) + { + } + Vector3Base(T (&in)[3]) : VectorNBase(in) + { + } + Vector3Base(const Eigen::Matrix& in) : VectorNBase(in) + { + } + Vector3Base(const VectorNBase& in) : VectorNBase(in) + { + } + + Vector3Base(T v1, T v2, T v3) + { + this->data[0] = v1; + this->data[1] = v2; + this->data[2] = v3; + } + + T X() const + { + return this->data[0]; + } + T Y() const + { + return this->data[1]; + } + T Z() const + { + return this->data[2]; + } + + inline Vector3Base Cross(const Vector3Base& v) const + { + return Vector3Base(-(*this)(2) * v(1) + (*this)(1) * v(2), (*this)(2) * v(0) - (*this)(0) * v(2), + -(*this)(1) * v(0) + (*this)(0) * v(1)); + } +}; + +inline Vector3Base operator*(const float& lhs, const Vector3Base& rhs) +{ + return Vector3Base(rhs * lhs); +} + +inline Vector3Base operator*(const double& lhs, const Vector3Base& rhs) +{ + return Vector3Base(rhs * lhs); +} + +template +inline VectorNBase Cross(const VectorNBase& v1, const VectorNBase& v2) +{ + return Vector3Base(v1).Cross(v2); +} + +typedef Vector3Base Vector3f; +typedef Vector3Base Vec3f; + +typedef Vector3Base Vector3d; +typedef Vector3Base Vec3d; + +typedef Vector3Base Vector3; +typedef Vector3Base Vec3; + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector4.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector4.h new file mode 100755 index 0000000..fa8cb2b --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/Vector4.h @@ -0,0 +1,63 @@ +#ifndef GEOMETRY_UTILS_VECTOR4_H +#define GEOMETRY_UTILS_VECTOR4_H + +#include "VectorNBase.h" + +namespace geometry_utils +{ +template +struct Vector4Base : VectorNBase +{ + Vector4Base() : VectorNBase() + { + } + Vector4Base(T val) : VectorNBase(val) + { + } + Vector4Base(const Vector4Base& in) : VectorNBase(in.data) + { + } + Vector4Base(const boost::array& in) : VectorNBase(in) + { + } + Vector4Base(T (&in)[4]) : VectorNBase(in) + { + } + Vector4Base(const Eigen::Matrix& in) : VectorNBase(in) + { + } + Vector4Base(const VectorNBase& in) : VectorNBase(in) + { + } + + Vector4Base(T v1, T v2, T v3, T v4) + { + this->data[0] = v1; + this->data[1] = v2; + this->data[2] = v3; + this->data[3] = v4; + } +}; + +inline Vector4Base operator*(const float& lhs, const Vector4Base& rhs) +{ + return Vector4Base(rhs * lhs); +} + +inline Vector4Base operator*(const double& lhs, const Vector4Base& rhs) +{ + return Vector4Base(rhs * lhs); +} + +typedef Vector4Base Vector4f; +typedef Vector4Base Vec4f; + +typedef Vector4Base Vector4d; +typedef Vector4Base Vec4d; + +typedef Vector4Base Vector4; +typedef Vector4Base Vec4; + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/VectorNBase.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/VectorNBase.h new file mode 100755 index 0000000..dba03ac --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/VectorNBase.h @@ -0,0 +1,280 @@ +#ifndef GEOMETRY_UTILS_VECTORN_H +#define GEOMETRY_UTILS_VECTORN_H + +#include "GeometryUtilsMath.h" +#include +#include +#include +#include +#include + +namespace geometry_utils +{ +template +struct VectorNBase +{ + typedef typename boost::shared_ptr> Ptr; + typedef typename boost::shared_ptr> ConstPtr; + + static const size_t length = N; + + boost::array data; + + VectorNBase() + { + data.fill(0); + } + + VectorNBase(T val) + { + data.fill(val); + } + + VectorNBase(const VectorNBase& in) : data(in.data) + { + } + + VectorNBase(const boost::array& in) : data(in) + { + } + + VectorNBase(T (&in)[N]) + { + for (size_t i = 0; i < N; i++) + data[i] = in[i]; + } + + VectorNBase(const Eigen::Matrix& in) + { + for (size_t i = 0; i < N; i++) + data[i] = in(i, 0); + } + + inline T& operator()(unsigned int i) + { + return data[i]; + } + + inline const T& operator()(unsigned int i) const + { + return data[i]; + } + + inline T& Get(unsigned int i) + { + return data[i]; + } + + inline const T& Get(unsigned int i) const + { + return data[i]; + } + + inline VectorNBase& operator=(const VectorNBase& rhs) + { + if (this == &rhs) + return *this; + data = rhs.data; + return *this; + } + + inline VectorNBase operator*(T rhs) const + { + T d[N]; + for (size_t i = 0; i < N; i++) + d[i] = data[i] * rhs; + return VectorNBase(d); + } + + inline VectorNBase operator+(const VectorNBase& rhs) const + { + T d[N]; + for (size_t i = 0; i < N; i++) + d[i] = data[i] + rhs.data[i]; + return VectorNBase(d); + } + + inline VectorNBase operator-() const + { + T d[N]; + for (size_t i = 0; i < N; i++) + d[i] = -data[i]; + return VectorNBase(d); + } + + inline VectorNBase operator-(const VectorNBase& rhs) const + { + T d[N]; + for (size_t i = 0; i < N; i++) + d[i] = data[i] - rhs.data[i]; + return VectorNBase(d); + } + + inline VectorNBase operator%(const VectorNBase& rhs) const + { + T d[N]; + for (size_t i = 0; i < N; i++) + d[i] = data[i] * rhs.data[i]; + return VectorNBase(d); + } + + inline T operator^(const VectorNBase& rhs) const + { + T dot = 0; + for (size_t i = 0; i < N; i++) + dot += data[i] * rhs.data[i]; + return dot; + } + + inline VectorNBase operator/(const VectorNBase& rhs) const + { + T d[N]; + for (size_t i = 0; i < N; i++) + d[i] = data[i] / rhs.data[i]; + return VectorNBase(d); + } + + inline VectorNBase operator+=(const VectorNBase& rhs) + { + for (size_t i = 0; i < N; i++) + data[i] += rhs.data[i]; + return *this; + } + + inline VectorNBase operator-=(const VectorNBase& rhs) + { + for (size_t i = 0; i < N; i++) + data[i] -= rhs.data[i]; + return *this; + } + + inline VectorNBase operator%=(const VectorNBase& rhs) + { + for (size_t i = 0; i < N; i++) + data[i] *= rhs.data[i]; + return *this; + } + + inline VectorNBase operator/=(const VectorNBase& rhs) + { + for (size_t i = 0; i < N; i++) + data[i] /= rhs.data[i]; + return *this; + } + + inline VectorNBase operator*=(const T& rhs) + { + for (size_t i = 0; i < N; i++) + data[i] *= rhs; + return *this; + } + + inline VectorNBase operator/=(const T& rhs) + { + for (size_t i = 0; i < N; i++) + data[i] /= rhs; + return *this; + } + + inline bool operator==(const VectorNBase& that) const + { + return this->Equals(that); + } + + inline bool operator!=(const VectorNBase& that) const + { + return !this->Equals(that); + } + + inline bool Equals(const VectorNBase& that, const T ptol = 1e-8) const + { + return (*this - that).Norm() < ptol; + } + + inline T Norm() const + { + return math::sqrt((*this) ^ (*this)); + } + + inline VectorNBase Normalize() const + { + return (*this) / Norm(); + } + + inline VectorNBase Abs() const + { + T d[N]; + for (size_t i = 0; i < N; i++) + d[i] = std::abs(data[i]); + return VectorNBase(d); + } + + inline void Ones() + { + data.fill(1); + } + + inline void Zeros() + { + data.fill(0); + } + + inline T Dot(const VectorNBase& v) const + { + return (*this) ^ v; + } + + inline VectorNBase Scale(T s) const + { + return (*this) * s; + } + + inline void Print(const std::string& prefix = std::string()) const + { + if (!prefix.empty()) + std::cout << prefix << std::endl; + std::cout << (*this) << std::endl; + } + + inline Eigen::Matrix Eigen() const + { + return Eigen::Matrix(data.data()); + } +}; + +template +inline VectorNBase operator*(const T& lhs, const VectorNBase& rhs) +{ + return rhs * lhs; +} + +template +inline std::ostream& operator<<(std::ostream& out, const VectorNBase& m) +{ + for (size_t i = 0; i < N - 1; i++) + out << m.data[i] << " "; + out << m.data[N - 1]; + return out; +} + +template +inline Eigen::Matrix Eigen(const VectorNBase& in) +{ + return in.Eigen(); +} + +template +inline T Norm(const VectorNBase& v) +{ + return v.Norm(); +} + +template +inline T Dot(const VectorNBase& v1, const VectorNBase& v2) +{ + return v1.Dot(v2); +} + +} // namespace geometry_utils + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/YAMLLoader.h b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/YAMLLoader.h new file mode 100755 index 0000000..608c625 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/geometry_utils/YAMLLoader.h @@ -0,0 +1,106 @@ +/* +geometry_utils: Utility library to provide common geometry types and +transformations Copyright (C) 2013 Nathan Michael 2016 Erik Nelson + +This program is free software; you can redistribute it and/or +modify it under the terms of the GNU General Public License +as published by the Free Software Foundation; either version 2 +of the License, or (at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. +*/ + +#ifndef GEOMETRY_UTILS_YAML_LOADER_H +#define GEOMETRY_UTILS_YAML_LOADER_H + +#ifdef __YAML_UTILS_H__ +#error "YAMLUtils must be included last" +#endif + +#include +#include + +namespace YAML +{ +template <> +struct convert +{ + static Node Encode(const geometry_utils::Vector2& rhs) + { + Node node; + node.push_back(rhs[0]); + node.push_back(rhs[1]); + return node; + } + + static bool Decode(const Node& node, geometry_utils::Vector2& rhs) + { + if (!node.IsSequence() || node.size() != 2) + return false; + + rhs[0] = node[0].as(); + rhs[1] = node[1].as(); + return true; + } +}; + +template <> +struct convert +{ + static Node Encode(const geometry_utils::Vector3& rhs) + { + Node node; + node.push_back(rhs[0]); + node.push_back(rhs[1]); + node.push_back(rhs[2]); + return node; + } + + static bool Decode(const Node& node, geometry_utils::Vector3& rhs) + { + if (!node.IsSequence() || node.size() != 3) + return false; + + rhs[0] = node[0].as(); + rhs[1] = node[1].as(); + rhs[2] = node[2].as(); + return true; + } +}; + +template <> +struct convert +{ + static Node Encode(const geometry_utils::Vector4& rhs) + { + Node node; + node.push_back(rhs[0]); + node.push_back(rhs[1]); + node.push_back(rhs[2]); + node.push_back(rhs[3]); + return node; + } + + static bool Decode(const Node& node, geometry_utils::Vector4& rhs) + { + if (!node.IsSequence() || node.size() != 4) + return false; + + rhs[0] = node[0].as(); + rhs[1] = node[1].as(); + rhs[2] = node[2].as(); + rhs[3] = node[3].as(); + return true; + } +}; + +} // namespace YAML + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/ikd_tree/ikd_Tree.h b/src/localization_module_lio_locus/include/lio_locus_humble/ikd_tree/ikd_Tree.h new file mode 100755 index 0000000..621c5ac --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/ikd_tree/ikd_Tree.h @@ -0,0 +1,240 @@ +#pragma once +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define EPSS 1e-6 +#define Minimal_Unbalanced_Tree_Size 10 +#define Multi_Thread_Rebuild_Point_Num 1500 +#define DOWNSAMPLE_SWITCH true +#define ForceRebuildPercentage 0.2 +#define Q_LEN 1000000 + +using namespace std; + +typedef pcl::PointXYZINormal PointType; +// typedef vector> PointVector; +typedef pcl::PointCloud PointVector; + +// struct PointType { +// float x, y, z; +// PointType(float px = 0.0f, float py = 0.0f, float pz = 0.0f) { +// x = px; +// y = py; +// z = pz; +// } +//}; + +// typedef vector PointVector; + +const PointType ZeroP; + +struct KD_TREE_NODE { + PointType point; + int division_axis; + int TreeSize = 1; + int invalid_point_num = 0; + int down_del_num = 0; + bool point_deleted = false; + bool tree_deleted = false; + bool point_downsample_deleted = false; + bool tree_downsample_deleted = false; + bool need_push_down_to_left = false; + bool need_push_down_to_right = false; + bool working_flag = false; + pthread_mutex_t push_down_mutex_lock; + float node_range_x[2], node_range_y[2], node_range_z[2]; + KD_TREE_NODE* left_son_ptr = nullptr; + KD_TREE_NODE* right_son_ptr = nullptr; + KD_TREE_NODE* father_ptr = nullptr; + // For paper data record + float alpha_del; + float alpha_bal; +}; + +struct PointType_CMP { + PointType point; + float dist = 0.0; + PointType_CMP(PointType p = ZeroP, float d = INFINITY) { + this->point = p; + this->dist = d; + }; + bool operator<(const PointType_CMP& a) const { + if (fabs(dist - a.dist) < 1e-10) + return point.x < a.point.x; + else + return dist < a.dist; + } +}; + +// struct BoxPointType { +// float vertex_min[3]; +// float vertex_max[3]; +//}; +struct BoxPointType { + Eigen::Vector3f vertex_min; + Eigen::Vector3f vertex_max; +}; +enum operation_set { + ADD_POINT, + DELETE_POINT, + DELETE_BOX, + ADD_BOX, + DOWNSAMPLE_DELETE, + PUSH_DOWN +}; + +enum delete_point_storage_set { + NOT_RECORD, + DELETE_POINTS_REC, + MULTI_THREAD_REC +}; + +struct Operation_Logger_Type { + PointType point; + BoxPointType boxpoint; + bool tree_deleted, tree_downsample_deleted; + operation_set op; +}; + +class MANUAL_Q { +private: + int head = 0, tail = 0, counter = 0; + Operation_Logger_Type q[Q_LEN]; + bool is_empty; + +public: + void pop(); + Operation_Logger_Type front(); + Operation_Logger_Type back(); + void clear(); + void push(Operation_Logger_Type op); + bool empty(); + int size(); +}; + +class MANUAL_HEAP { +public: + MANUAL_HEAP(int max_capacity = 100); + ~MANUAL_HEAP(); + void pop(); + PointType_CMP top(); + void push(PointType_CMP point); + int size(); + void clear(); + +private: + PointType_CMP* heap; + void MoveDown(int heap_index); + void FloatUp(int heap_index); + int heap_size = 0; + int cap = 0; +}; + +class KD_TREE { +private: + // Multi-thread Tree Rebuild + bool termination_flag = false; + bool rebuild_flag = false; + pthread_t rebuild_thread; + pthread_mutex_t termination_flag_mutex_lock, rebuild_ptr_mutex_lock, + working_flag_mutex, search_flag_mutex; + pthread_mutex_t rebuild_logger_mutex_lock, points_deleted_rebuild_mutex_lock; + // queue Rebuild_Logger; + MANUAL_Q Rebuild_Logger; + PointVector Rebuild_PCL_Storage; + KD_TREE_NODE** Rebuild_Ptr = nullptr; + int search_mutex_counter = 0; + static void* multi_thread_ptr(void* arg); + void multi_thread_rebuild(); + void start_thread(); + void stop_thread(); + void run_operation(KD_TREE_NODE** root, Operation_Logger_Type operation); + // KD Tree Functions and augmented variables + int Treesize_tmp = 0, Validnum_tmp = 0; + float alpha_bal_tmp = 0.5, alpha_del_tmp = 0.0; + float delete_criterion_param = 0.5f; + float balance_criterion_param = 0.7f; + float downsample_size = 0.2f; + bool Delete_Storage_Disabled = false; + KD_TREE_NODE* STATIC_ROOT_NODE = nullptr; + PointVector Points_deleted; + PointVector Downsample_Storage; + PointVector Multithread_Points_deleted; + void InitTreeNode(KD_TREE_NODE* root); + void Test_Lock_States(KD_TREE_NODE* root); + void BuildTree(KD_TREE_NODE** root, int l, int r, PointVector& Storage); + void Rebuild(KD_TREE_NODE** root); + int Delete_by_range(KD_TREE_NODE** root, + BoxPointType boxpoint, + bool allow_rebuild, + bool is_downsample); + void + Delete_by_point(KD_TREE_NODE** root, PointType point, bool allow_rebuild); + void Add_by_point(KD_TREE_NODE** root, + PointType point, + bool allow_rebuild, + int father_axis); + void + Add_by_range(KD_TREE_NODE** root, BoxPointType boxpoint, bool allow_rebuild); + void Search(KD_TREE_NODE* root, + int k_nearest, + PointType point, + MANUAL_HEAP& q, + double max_dist); // priority_queue + void Search_by_range(KD_TREE_NODE* root, + BoxPointType boxpoint, + PointVector& Storage); + bool Criterion_Check(KD_TREE_NODE* root); + void Push_Down(KD_TREE_NODE* root); + void Update(KD_TREE_NODE* root); + void delete_tree_nodes(KD_TREE_NODE** root); + void downsample(KD_TREE_NODE** root); + bool same_point(PointType a, PointType b); + float calc_dist(PointType a, PointType b); + float calc_box_dist(KD_TREE_NODE* node, PointType point); + static bool point_cmp_x(PointType a, PointType b); + static bool point_cmp_y(PointType a, PointType b); + static bool point_cmp_z(PointType a, PointType b); + +public: + KD_TREE(float delete_param = 0.5, + float balance_param = 0.6, + float box_length = 0.2); + ~KD_TREE(); + void Set_delete_criterion_param(float delete_param); + void Set_balance_criterion_param(float balance_param); + void set_downsample_param(float box_length); + void InitializeKDTree(float delete_param = 0.5, + float balance_param = 0.7, + float box_length = 0.2); + int size(); + int validnum(); + void root_alpha(float& alpha_bal, float& alpha_del); + void Build(PointVector point_cloud); + void Nearest_Search(PointType point, + int k_nearest, + PointVector& Nearest_Points, + vector& Point_Distance, + double max_dist = INFINITY); + int Add_Points(PointVector& PointToAdd, bool downsample_on); + void Add_Point_Boxes(vector& BoxPoints); + void Delete_Points(PointVector& PointToDel); + int Delete_Point_Boxes(vector& BoxPoints); + void flatten(KD_TREE_NODE* root, + PointVector& Storage, + delete_point_storage_set storage_type); + void acquire_removed_points(PointVector& removed_points); + BoxPointType tree_range(); + PointVector PCL_Storage; + KD_TREE_NODE* Root_Node = nullptr; + int max_queue_size = 0; +}; diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/cloud_pre_processor.h b/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/cloud_pre_processor.h new file mode 100755 index 0000000..af7e990 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/cloud_pre_processor.h @@ -0,0 +1,127 @@ +/* + * cloud_pre_processor.h + * + * Created on: Oct 17, 2025 + * Author: solomon + */ + +#ifndef PACKAGES_LIO_LOCUS_INCLUDE_LIO_LOCUS_CLOUD_PRE_PROCESSOR_H_ +#define PACKAGES_LIO_LOCUS_INCLUDE_LIO_LOCUS_CLOUD_PRE_PROCESSOR_H_ + +// headers for ROS; +#include +#include +#include + +// headers for PCL; +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// headers for convenience; +#include +#include + +#include + +#include "lio_locus/parameter_loading.h" +#include + + +// define data type to store customized lidar data; +namespace robosense_ros { +struct EIGEN_ALIGN16 Point { + PCL_ADD_POINT4D + ; + float intensity; + double timestamp; + uint16_t ring;EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; +} // namespace velodyne_ros +POINT_CLOUD_REGISTER_POINT_STRUCT(robosense_ros::Point, + (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(double, timestamp, timestamp) // of 64-bits + (uint16_t, ring, ring)) + +namespace livox_lidar { +struct EIGEN_ALIGN16 Point { + PCL_ADD_POINT4D + ; + float intensity; + uint8_t line; + uint8_t tag; + double timestamp;EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; +} // namespace velodyne_ros +POINT_CLOUD_REGISTER_POINT_STRUCT(livox_lidar::Point, + (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(double, timestamp, timestamp) (uint8_t, tag, tag)(uint8_t, line, line)) + +class CloudPreProcessor { +public: + CloudPreProcessor(); + virtual ~CloudPreProcessor(); + typedef boost::shared_ptr Ptr; + + // convert ROS cloud message to PCL cloud format; + static pcl::PointCloud::Ptr adaptCloudForm( + const sensor_msgs::msg::PointCloud2 &cloud_input); + + static pcl::PointCloud::Ptr adaptCloudFormFromLivoxCloud( + const sensor_msgs::msg::PointCloud2 &cloud_input); + + // attention: curvature segment to store time difference for each laser beam; + static pcl::PointCloud::Ptr transformCloudCartesian( + pcl::PointCloud::Ptr cloud_input, + tf2::Transform T); + + // combo unique interface for transformation and normal vector calculation; + bool transformCloudWithNormalCalculation( + pcl::PointCloud::Ptr cloud_input, + tf2::Transform T, + pcl::PointCloud::Ptr &cloud_normals); + + inline void setCloudPreProcessingParameters(double leaf_voxel_filtering, + double filter_limit, int size_cores, int size_k_search, + double radius_search) { + leaf_voxel_filtering_ = leaf_voxel_filtering; + filter_limit_ = filter_limit; + + size_cores_ = size_cores; + size_k_search_ = size_k_search; + radius_search_ = radius_search; + + LOG(INFO) << "... leaf_voxel_filtering_ -> [" + << leaf_voxel_filtering_ << "]"; + LOG(INFO) << "... filter_limit_ -> " << filter_limit_ << "]"; + LOG(INFO) << "... size_k_search_ -> [" << size_k_search_ << "]"; + LOG(INFO) << "... radius_search_ -> [" << radius_search_ << "]"; + LOG(INFO) << "... size_cores_ -> [" << size_cores_ << "]"; + } + + inline void setLogPath(std::string path) { + path_log = path; + } + +private: + bool doVoxelGridFilteringAndComputeNormals( + pcl::PointCloud::Ptr input, + pcl::PointCloud::Ptr &cloud_normals); + + boost::mutex mutex_; + int size_cores_ { 3 }; + double leaf_voxel_filtering_ { 0.6 }; + int size_k_search_ { 20 }; + double radius_search_ { 0 }; + double filter_limit_ { 100 }; + + std::string path_log { "" }; + + std::string log_tag { "cloud pre-processing" }; +}; + +#endif /* PACKAGES_LIO_LOCUS_INCLUDE_LIO_LOCUS_CLOUD_PRE_PROCESSOR_H_ */ diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/complementary_filter.h b/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/complementary_filter.h new file mode 100755 index 0000000..1a804a4 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/complementary_filter.h @@ -0,0 +1,184 @@ +/* + @author Roberto G. Valenti + + @section LICENSE + Copyright (c) 2015, City University of New York + CCNY Robotics Lab + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef IMU_TOOLS_COMPLEMENTARY_FILTER_H +#define IMU_TOOLS_COMPLEMENTARY_FILTER_H + +#include "lio_locus/parameter_loading.h" +#include +#include + +using std::string; + +namespace imu_tools { + +class ComplementaryFilter { +public: + ComplementaryFilter(); + virtual ~ComplementaryFilter(); + + bool setGainAcc(double gain); + bool setGainMag(double gain); + double getGainAcc() const; + double getGainMag() const; + + bool setBiasAlpha(double bias_alpha); + double getBiasAlpha() const; + + // When the filter is in the steady state, bias estimation will occur (if + // the parameter is enabled). + bool getSteadyState() const; + + void setDoBiasEstimation(bool do_bias_estimation); + bool getDoBiasEstimation() const; + + void setDoAdaptiveGain(bool do_adaptive_gain); + bool getDoAdaptiveGain() const; + + double getAngularVelocityBiasX() const; + double getAngularVelocityBiasY() const; + double getAngularVelocityBiasZ() const; + + // Set the orientation, as a Hamilton Quaternion, of the body frame wrt the + // fixed frame. + void setOrientation(double q0, double q1, double q2, double q3); + + // Get the orientation, as a Hamilton Quaternion, of the body frame wrt the + // fixed frame. + void getOrientation(double &q0, double &q1, double &q2, double &q3) const; + + // Update from accelerometer and gyroscope data. + // [ax, ay, az]: Normalized gravity vector. + // [wx, wy, wz]: Angular veloctiy, in rad / s. + // dt: time delta, in seconds. + void update(double ax, double ay, double az, double wx, double wy, + double wz, double dt); + + // Update from accelerometer, gyroscope, and magnetometer data. + // [ax, ay, az]: Normalized gravity vector. + // [wx, wy, wz]: Angular veloctiy, in rad / s. + // [mx, my, mz]: Magnetic field, units irrelevant. + // dt: time delta, in seconds. + void update(double ax, double ay, double az, double wx, double wy, + double wz, double mx, double my, double mz, double dt); + + inline void setLogPath(string path) { + path_log = path; + } + +private: + static const double kGravity; + static const double gamma_; + // Bias estimation steady state thresholds + static const double kAngularVelocityThreshold; + static const double kAccelerationThreshold; + static const double kDeltaAngularVelocityThreshold; + + string path_log { "" }; + + // Gain parameter for the complementary filter, belongs in [0, 1]. + double gain_acc_; + double gain_mag_; + + // Bias estimation gain parameter, belongs in [0, 1]. + double bias_alpha_; + + // Parameter whether to do bias estimation or not. + bool do_bias_estimation_; + + // Parameter whether to do adaptive gain or not. + bool do_adaptive_gain_; + + bool initialized_; + bool steady_state_; + + // The orientation as a Hamilton quaternion (q0 is the scalar). Represents + // the orientation of the fixed frame wrt the body frame. + double q0_, q1_, q2_, q3_; + + // Bias in angular velocities; + double wx_prev_, wy_prev_, wz_prev_; + + // Bias in angular velocities; + double wx_bias_, wy_bias_, wz_bias_; + + void updateBiases(double ax, double ay, double az, double wx, double wy, + double wz); + + bool checkState(double ax, double ay, double az, double wx, double wy, + double wz) const; + + void getPrediction(double wx, double wy, double wz, double dt, + double &q0_pred, double &q1_pred, double &q2_pred, + double &q3_pred) const; + + void getMeasurement(double ax, double ay, double az, double &q0_meas, + double &q1_meas, double &q2_meas, double &q3_meas); + + void getMeasurement(double ax, double ay, double az, double mx, double my, + double mz, double &q0_meas, double &q1_meas, double &q2_meas, + double &q3_meas); + + void getAccCorrection(double ax, double ay, double az, double p0, double p1, + double p2, double p3, double &dq0, double &dq1, double &dq2, + double &dq3); + + void getMagCorrection(double mx, double my, double mz, double p0, double p1, + double p2, double p3, double &dq0, double &dq1, double &dq2, + double &dq3); + + double getAdaptiveGain(double alpha, double ax, double ay, double az); +}; + +// Utility math functions: + +void normalizeVector(double &x, double &y, double &z); + +void normalizeQuaternion(double &q0, double &q1, double &q2, double &q3); + +void scaleQuaternion(double gain, double &dq0, double &dq1, double &dq2, + double &dq3); + +void invertQuaternion(double q0, double q1, double q2, double q3, + double &q0_inv, double &q1_inv, double &q2_inv, double &q3_inv); + +void quaternionMultiplication(double p0, double p1, double p2, double p3, + double q0, double q1, double q2, double q3, double &r0, double &r1, + double &r2, double &r3); + +void rotateVectorByQuaternion(double x, double y, double z, double q0, + double q1, double q2, double q3, double &vx, double &vy, double &vz); + +} // namespace imu_tools + +#endif // IMU_TOOLS_COMPLEMENTARY_FILTER_H diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/lio_locus.h b/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/lio_locus.h new file mode 100755 index 0000000..ed740e8 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/lio_locus.h @@ -0,0 +1,231 @@ +/* + * lio_locus.h + * + * Created on: Sep 11, 2025 + * Author: solomon + */ + +#ifndef PACKAGES_TEST_LOCUS_SRC_LIO_LOCUS_H_ +#define PACKAGES_TEST_LOCUS_SRC_LIO_LOCUS_H_ + +// dependency headers; +#include +#include + +//#include +//#include +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "lio_locus/parameter_loading.h" + +#include + +using std::string; +using std::map; + +using point_cloud_odometry::PointCloudOdometry; +using point_cloud_localization::PointCloudLocalization; + +typedef pcl::PointCloud PointCloudType; +typedef boost::shared_ptr PointCloudOdometryPtr; +typedef boost::shared_ptr PointCloudLocalizationPtr; +typedef boost::shared_ptr PointCloudIkdTreeMapperPtr; +// typedef boost::shared_ptr PointCloudMultiThreadedMapperPtr; +// typedef boost::shared_ptr PointCloudMapperPtr; + +#include +#include + +namespace lio_locus { + +struct IMUData { + IMUData() { + } + + IMUData(double ts, double qx, double qy, double qz, double qw) { + + timestamp_ = ts; + + orientation.x() = qx; + orientation.y() = qy; + orientation.z() = qz; + orientation.w() = qw; + } + + Eigen::Quaterniond orientation { Eigen::Quaterniond::Identity() }; + double timestamp_; +}; + +struct TransformStamped { + + TransformStamped() { + } + + TransformStamped(geometry_utils::Transform3 T, std::uint64_t timestamp_) { + pose = T; + timestamp = timestamp_; + } + + geometry_utils::Transform3 pose { geometry_utils::Transform3::Identity() }; + std::uint64_t timestamp { 0 }; // PCL time stamp; +}; + +class LioLocus { +public: + LioLocus(); + virtual ~LioLocus(); + typedef boost::shared_ptr Ptr; + + //------------------------------------------------------------------ + // initialization; + bool initialize(string path_to_param); + // data feeding; + void feedIMUData(IMUData imu_data); + //------------------------------------------------------------------ + // cloud map in memory is updated; + void trackCurrentCloudWithOnlineBuiltMap(PointCloudType::Ptr msg_cloud); + //------------------------------------------------------------------ + // to fresh memory cloud with data storage; + bool uploadPriorCloudMap(string fn_cloud_map, double leaf_size); + // for re-localization; + void setPosePrior(geometry_utils::Transform3 pose_prior); + // cloud map in memory is not updated; + bool trackCurrentCloudWithPriorCloudMap(PointCloudType::Ptr msg_cloud); + + void clearCloudMapInMemory(); + + bool saveCloudMapInMemory(string path, bool flag_voxel_filtering = false, + double leaf_size = 0.5); + + //=============================================================================== + // data retrieval; + + bool getCloudMapInMemory(PointCloudType::Ptr cloud); + + static PointCloudType::Ptr downsampleCloud(PointCloudType::Ptr input_cloud, + double leaf_size); + + inline TransformStamped getTimestampedLatestPose() { + return m_pose_latest; + } + + // Pose6DOF getCurrentPose6DOF(); + + inline void printCurrentPose() { + + auto loc = getTimestampedLatestPose().pose; + + LOG(INFO) << "... current pose -> #[" << loc.translation.X() << "," + << loc.translation.Y() << "," << loc.rotation.Yaw() << "]"; + } + inline int showImuBufferSize() { + return m_imus.size(); + } + + inline PointCloudType::Ptr getLatestLocalizedCloud() { + return mp_cloud_incremental; + } + + //------------------------------------------------------------------ + // to use flat ground assumption or not; + inline void setFlatGroundAssumption(bool flag) { + mb_set_flat_ground = flag; + mp_cloud_odometry->SetFlatGroundAssumptionValue(mb_set_flat_ground); + mp_cloud_localization->SetFlatGroundAssumptionValue(mb_set_flat_ground); + } + + // to use imu prior for delta transform updating or not; + inline void setUseIMU(bool flag) { + mb_use_imu = flag; + + } + + // to use scan-to-scan matching for delta transform updating or not; + inline void setUseScan2ScanMatching(bool flag) { + mb_use_scan2scan_matching = flag; + } + + inline void setThresholds(double trans, double rot) { + m_threshold_trans_map = trans; + m_threshold_rot_map = rot; + } + + inline void setIMU2CloudExtrinsic(Eigen::Quaterniond quat) { + m_dq_imu2cloud = quat; + } + + inline void printIMU2CloudExtrinsic() { + Eigen::Matrix3d T = m_dq_imu2cloud.toRotationMatrix(); + geometry_utils::Rot3 rot_gu = geometry_utils::Rot3(T(0, 0), T(0, 1), + T(0, 2), T(1, 0), T(1, 1), T(1, 2), T(2, 0), T(2, 1), T(2, 2)); + + LOG(INFO) << "... orientation for extrinsic -> RPY [" + << rot_gu.Roll() << "," << rot_gu.Pitch() << "," << rot_gu.Yaw() + << "]"; + } + + inline void setPathLog(string path) { + path_log = path; + } + + //=============================================================================== + +private: + void setPath2Parameters(string path_to_param); + bool getRelativeRotationFromIMU(double ts, + geometry_utils::Quaterniond &quat_imu); + Eigen::Matrix3d toRotationMatrix(geometry_utils::Quaterniond quat_imu); + bool getMessageAtTimeStamp(double stamp, IMUData &msg, + map buffer); + void transformCloudAndInsertToMap(PointCloudType::Ptr msg_cloud); + + // to store input data; + map m_imus; + int m_size_imus { 20000 }; + Eigen::Quaterniond m_dq_imu2cloud { Eigen::Quaterniond::Identity() }; + string m_path_to_file { "" }; + + // flags; + bool mb_use_scan2scan_matching { true }; + bool mb_use_imu { false }; + bool mb_tracker_reset { false }; + bool mb_set_flat_ground { false }; + + // cloud map update thresholds; + double m_threshold_trans_map { 0.5 }; + double m_threshold_rot_map { 20.0 / 180.0 * M_PI }; + + string log_tag { "lio-locus" }; + string path_log { "" }; + + // incrementally localized cloud; + PointCloudType::Ptr mp_cloud_incremental; + + TransformStamped m_pose_latest; + + // dependency processors; + PointCloudOdometryPtr mp_cloud_odometry; + PointCloudLocalizationPtr mp_cloud_localization; + PointCloudIkdTreeMapperPtr mp_cloud_mapper; + +// shared_ptr mp_cloud_mapper; + +// PointCloudMapperPtr mp_cloud_mapper; +// PointCloudMultiThreadedMapperPtr mp_cloud_mapper; + +}; + +} + +#endif /* PACKAGES_TEST_LOCUS_SRC_LIO_LOCUS_H_ */ diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/parameter_loading.h b/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/parameter_loading.h new file mode 100755 index 0000000..887fe08 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/lio_locus/parameter_loading.h @@ -0,0 +1,430 @@ +#include + +#include + +#include +#include + +#include + +// for time consumption logging; +#include + +using std::string; + +struct ParameterLioLocus { + + ParameterLioLocus() { + } + + string log_tag { "pure-lo-locus-ros2" }; + + string topic_cloud { "/cloud_input" }; + string topic_imu { "/imu_filtered" }; + string frame_id_world; + string frame_id_ego; + + bool flag_save_map_in_memory { false }; + string path_save_map { "" }; + string fn_save_cloud_map { "" }; + bool flag_voxel_filtering { false }; + double leaf_size { 0.5 }; + + int freq_cloud_proc { 10 }; + + bool flag_arranged_proc { true }; + + // thresholds for mapping pose recording; + double threshold_trans_map { 0.5 }; + double threshold_rot_map { 10.0 / 180.0 * M_PI }; + + // thresholds for trajectory pose recording; + double threshold_trans_traj { 0.2 }; + double threshold_rot_traj { 5.0 / 180.0 * M_PI }; + + bool flag_use_imu { false }; + bool flag_use_scan2scan_matching { true }; + + bool flag_use_prior_map { false }; + string fn_cloud_map { "" }; + double ratio_fresh_map { 1.2 }; + + string path_log { "" }; + + double leaf_size_load_map { 0.5 }; + double leaf_size_vis_map { 0.5 }; + + double ext_imu2lidar_dx { 0.0 }; + double ext_imu2lidar_dy { 0.0 }; + double ext_imu2lidar_dz { 0.0 }; + double ext_imu2lidar_droll { 0.0 }; + double ext_imu2lidar_dpitch { 0.0 }; + double ext_imu2lidar_dyaw { 0.0 }; +}; + +bool loadParametersFromFileForLioLocus(std::string path_to_file, + ParameterLioLocus ¶ms_lio_locus); + +using std::string; + +struct ParameterCloudPreprocessing { + ParameterCloudPreprocessing() { + } + + std::string log_tag { "cloud_preprocessor" }; + + bool pub_cloud_preproc { false }; + + string topic_cloud_raw { "/rsm1_1" }; + string topic_cloud { "/cloud_input" }; + string frame_id_base { "base_link" }; + + string path_log { "" }; + + double leaf_voxel_filtering { 0.6 }; + double filter_limit { 100 }; + + int size_cores { 6 }; + + int size_k_search_knn { 20 }; + double radius_search_knn { 0 }; + + double ext_tx; + double ext_ty; + double ext_tz; + + double ext_roll; + double ext_pitch; + double ext_yaw; + +}; + +bool loadParametersFromFileForCloudPreprocessing(std::string path_to_file, + ParameterCloudPreprocessing ¶ms_cloud_preproc); + +struct ParameterImuPreprocessing { + + ParameterImuPreprocessing() { + } + + std::string log_tag { "imu_preprocessor" }; + + string topic_imu_raw { "/imu" }; + string path_log { "" }; + + bool pub_imu_preproc { true }; + + bool do_bias_estimation { true }; + bool do_adaptive_gain { true }; + double bias_alpha { 0.01 }; + double orientation_stddev { 0.0 }; + bool flag_publish_tf { false }; + std::string frame_fixed { "fixed_imu" }; +}; + +bool loadParametersFromFileForIMUPreprocessing(std::string path_to_file, + ParameterImuPreprocessing ¶ms_imu_preproc); + +using std::string; +void writeDt2LogFile(string path, string fn, double dt); +//------------------------------------------------------------------------------------------- + +bool loadParametersFromFileForLioLocus(std::string path_to_file, + ParameterLioLocus ¶ms_lio_locus) { + if (!boost::filesystem::exists(path_to_file)) { + LOG(INFO) << "... parameter file NOT exists -> [" << path_to_file + << "]"; + return false; + } else { + LOG(INFO) << "... reading parameter from file -> [" << path_to_file + << "]"; + } + + LOG(INFO) + << "............................. parameters for lio locus ............................."; + + LOG(INFO) << "... reading parameter for lidar odometry from [" + << path_to_file << "]"; + + YAML::Node yaml_node = YAML::LoadFile(path_to_file); + auto yn = yaml_node["ros2_wrapper"]; + + params_lio_locus.path_log = yn["path_log"].as(); + LOG(INFO) << "... path_log -> [" + << params_lio_locus.path_log << "]"; + + params_lio_locus.flag_save_map_in_memory = yn["flag_save_map_in_memory"].as< + bool>(); + LOG(INFO) << "... flag_save_map_in_memory -> [" + << params_lio_locus.flag_save_map_in_memory << "]"; + + params_lio_locus.path_save_map = yn["path_save_map"].as(); + LOG(INFO) << "... path_save_map -> [" << params_lio_locus.path_save_map + << "]"; + + params_lio_locus.fn_save_cloud_map = yn["fn_save_cloud_map"].as(); + LOG(INFO) << "... fn_save_cloud_map -> [" + << params_lio_locus.fn_save_cloud_map << "]"; + + params_lio_locus.flag_voxel_filtering = + yn["flag_voxel_filtering"].as(); + LOG(INFO) << "... flag_voxel_filtering -> [" + << params_lio_locus.flag_voxel_filtering << "]"; + + params_lio_locus.leaf_size = yn["leaf_size"].as(); + LOG(INFO) << "... leaf_size -> [" << params_lio_locus.leaf_size << "]"; + + params_lio_locus.ratio_fresh_map = yn["ratio_fresh_map"].as(); + LOG(INFO) << "... ratio_fresh_map -> [" + << params_lio_locus.ratio_fresh_map << "]"; + + params_lio_locus.freq_cloud_proc = yn["freq_cloud_proc"].as(); + LOG(INFO) << "... freq_cloud_proc -> [" + << params_lio_locus.freq_cloud_proc << "]"; + + params_lio_locus.topic_cloud = yn["topic_cloud"].as(); + LOG(INFO) << "... topic_cloud -> [" << params_lio_locus.topic_cloud + << "]"; + + params_lio_locus.topic_imu = yn["topic_imu"].as(); + LOG(INFO) << "... topic_imu -> [" << params_lio_locus.topic_imu << "]"; + + params_lio_locus.frame_id_world = yn["frame_id_world"].as(); + LOG(INFO) << "... params_lio_locus.frame_id_world -> [" + << params_lio_locus.frame_id_world << "]"; + + params_lio_locus.frame_id_ego = yn["frame_id_ego"].as(); + LOG(INFO) << "... frame_id_ego -> [" << params_lio_locus.frame_id_ego + << "]"; + + // parameter for certain flags; + params_lio_locus.flag_use_imu = yn["flag_use_imu"].as(); + LOG(INFO) << "... flag_use_imu -> [" << params_lio_locus.flag_use_imu + << "]"; + + params_lio_locus.flag_use_scan2scan_matching = + yn["flag_use_scan2scan_matching"].as(); + LOG(INFO) << "... flag_use_scan2scan_matching -> [" + << params_lio_locus.flag_use_scan2scan_matching << "]"; + + params_lio_locus.flag_arranged_proc = yn["flag_arranged_proc"].as(); + LOG(INFO) << "... flag_arranged_proc -> [" + << params_lio_locus.flag_arranged_proc << "]"; + + // parameter for cloud map loading; + params_lio_locus.flag_use_prior_map = yn["flag_use_prior_map"].as(); + LOG(INFO) << "... flag_use_prior_map -> [" + << params_lio_locus.flag_use_prior_map << "]"; + + string path_map, nm_map; + path_map = yn["path_cloud_map"].as(); + nm_map = yn["fn_cloud_map"].as(); + params_lio_locus.fn_cloud_map = path_map + "/" + nm_map; + LOG(INFO) << "... path_to_map -> [" << params_lio_locus.fn_cloud_map + << "]"; + + params_lio_locus.leaf_size_vis_map = yn["leaf_size_vis_map"].as(); + LOG(INFO) << "... leaf size load map -> [" + << params_lio_locus.leaf_size_vis_map << "]"; + + params_lio_locus.leaf_size_load_map = yn["leaf_size_load_map"].as(); + LOG(INFO) << "... leaf size load map -> [" + << params_lio_locus.leaf_size_load_map << "]"; + + // parameters for cloud map generation; + params_lio_locus.threshold_trans_map = + yn["threshold_trans_map"].as(); + LOG(INFO) << "... threshold_trans_map -> [" + << params_lio_locus.threshold_trans_map << "]"; + + params_lio_locus.threshold_rot_map = yn["threshold_rot_map"].as(); + LOG(INFO) << "... threshold_rot_map -> [" + << params_lio_locus.threshold_rot_map << "]"; + + params_lio_locus.threshold_trans_traj = + yn["threshold_trans_traj"].as(); + LOG(INFO) << "... threshold_trans_traj -> [" + << params_lio_locus.threshold_trans_traj << "]"; + + params_lio_locus.threshold_rot_traj = yn["threshold_rot_traj"].as(); + LOG(INFO) << "... threshold_rot_traj -> [" + << params_lio_locus.threshold_rot_traj << "]"; + + auto imu2lidar = yn["imu_to_lidar"]; + + params_lio_locus.ext_imu2lidar_dx = imu2lidar["tx"].as(); + params_lio_locus.ext_imu2lidar_dy = imu2lidar["ty"].as(); + params_lio_locus.ext_imu2lidar_dz = imu2lidar["tz"].as(); + params_lio_locus.ext_imu2lidar_droll = imu2lidar["r"].as(); + params_lio_locus.ext_imu2lidar_dpitch = imu2lidar["p"].as(); + params_lio_locus.ext_imu2lidar_dyaw = imu2lidar["y"].as(); + LOG(INFO) << "... imu2lidar translation extrinsic -> [" + << params_lio_locus.ext_imu2lidar_dx << "," + << params_lio_locus.ext_imu2lidar_dy << "," + << params_lio_locus.ext_imu2lidar_dz << "]"; + + LOG(INFO) << "... imu2lidar orientation extrinsic -> [" + << params_lio_locus.ext_imu2lidar_droll << "," + << params_lio_locus.ext_imu2lidar_dpitch << "," + << params_lio_locus.ext_imu2lidar_dyaw << "]"; + + return true; +} + +bool loadParametersFromFileForCloudPreprocessing(std::string path_to_file, + ParameterCloudPreprocessing ¶ms_cloud_preproc) { + + if (!boost::filesystem::exists(path_to_file)) { + + LOG(INFO) << "... parameter file NOT exists -> [" << path_to_file + << "]"; + + return false; + } else { + LOG(INFO) << "... reading parameter from file -> [" << path_to_file + << "]"; + } + + LOG(INFO) + << "............................. parameters for cloud preprocessing ............................."; + + // loading parameters; + YAML::Node yaml_node = YAML::LoadFile(path_to_file); + + //--------------------------------------------------------------------------- + // for cloud pre-processing parameters; + auto yn_ros = yaml_node["ros2_wrapper"]; + + params_cloud_preproc.path_log = yn_ros["path_log"].as(); + LOG(INFO) << "... path log -> [" << params_cloud_preproc.path_log + << "]"; + + params_cloud_preproc.topic_cloud_raw = + yn_ros["topic_cloud_raw"].as(); + LOG(INFO) << "... topic_cloud_raw -> [" + << params_cloud_preproc.topic_cloud_raw << "]"; + + params_cloud_preproc.topic_cloud = yn_ros["topic_cloud"].as(); + LOG(INFO) << "... topic_cloud -> [" << params_cloud_preproc.topic_cloud + << "]"; + + auto yn = yaml_node["cloud_preprocessing"]; + + params_cloud_preproc.pub_cloud_preproc = yn["pub_cloud_preproc"].as(); + + params_cloud_preproc.size_cores = yn["size_cores"].as(); + LOG(INFO) << "... size_cores -> [" << params_cloud_preproc.size_cores + << "]"; + + params_cloud_preproc.filter_limit = yn["filter_limit"].as(); + + params_cloud_preproc.leaf_voxel_filtering = yn["leaf_voxel_filtering"].as< + double>(); + LOG(INFO) << "... leaf_voxel_filtering -> [" + << params_cloud_preproc.leaf_voxel_filtering << "]"; + + params_cloud_preproc.size_k_search_knn = yn["size_k_search_knn"].as(); + LOG(INFO) << "... size_k_search_knn -> [" + << params_cloud_preproc.size_k_search_knn << "]"; + + params_cloud_preproc.radius_search_knn = + yn["radius_search_knn"].as(); + LOG(INFO) << "... radius_search_knn -> [" + << params_cloud_preproc.radius_search_knn << "]"; + + params_cloud_preproc.frame_id_base = + yaml_node["ros2_wrapper"]["frame_id_ego"].as(); + LOG(INFO) << "... frame_id_base -> [" + << params_cloud_preproc.frame_id_base << "]"; + //--------------------------------------------------------------------------- + // for extrinsic parameters; + auto extrinsic_lidar = yaml_node["ros2_wrapper"]["baselink_to_lidar"]; + params_cloud_preproc.ext_tx = extrinsic_lidar["tx"].as(); + params_cloud_preproc.ext_ty = extrinsic_lidar["ty"].as(); + params_cloud_preproc.ext_tz = extrinsic_lidar["tz"].as(); + + params_cloud_preproc.ext_pitch = extrinsic_lidar["p"].as(); + params_cloud_preproc.ext_roll = extrinsic_lidar["r"].as(); + params_cloud_preproc.ext_yaw = extrinsic_lidar["y"].as(); + + double ratio = M_PI / 180.0; + params_cloud_preproc.ext_roll *= ratio; + params_cloud_preproc.ext_pitch *= ratio; + params_cloud_preproc.ext_yaw *= ratio; + + //--------------------------------------------------------------------------- + + return true; +} + +bool loadParametersFromFileForIMUPreprocessing(std::string path_to_file, + ParameterImuPreprocessing ¶ms_imu_preproc) { + + if (!boost::filesystem::exists(path_to_file)) { + + LOG(INFO) << "... parameter file NOT exists -> [" << path_to_file + << "]"; + + return false; + } else { + LOG(INFO) << "... reading parameter from file -> [" << path_to_file + << "]"; + } + + LOG(INFO) + << "............................. parameters for imu preprocessing ............................."; + + YAML::Node yaml_node = YAML::LoadFile(path_to_file); + + auto yn_ros = yaml_node["ros2_wrapper"]; + params_imu_preproc.topic_imu_raw = yn_ros["topic_imu_raw"].as(); + params_imu_preproc.path_log = yn_ros["path_log"].as(); + + auto yn = yaml_node["imu_complementary_filtering"]; + params_imu_preproc.pub_imu_preproc = yn["pub_imu_preproc"].as(); + params_imu_preproc.do_adaptive_gain = yn["do_adaptive_gain"].as(); + + LOG(INFO) << "... do_adaptive_gain -> [" + << params_imu_preproc.do_adaptive_gain << "]"; + + params_imu_preproc.do_bias_estimation = yn["do_bias_estimation"].as(); + LOG(INFO) << "... do_bias_estimation -> [" + << params_imu_preproc.do_bias_estimation << "]"; + + params_imu_preproc.bias_alpha = yn["bias_alpha"].as(); + LOG(INFO) << "... bias_alpha -> [" << params_imu_preproc.bias_alpha + << "]"; + + params_imu_preproc.flag_publish_tf = yn["flag_publish_tf"].as(); + LOG(INFO) << "... flag_publish_tf -> [" + << params_imu_preproc.flag_publish_tf << "]"; + + params_imu_preproc.frame_fixed = yn["frame_fixed_"].as(); + + params_imu_preproc.orientation_stddev = + yn["orientation_stddev"].as(); + + return true; +} + +void writeDt2LogFile(string path, string fn, double dt) { + // logging to file; + boost::filesystem::path path_cloud(path); + if (!boost::filesystem::exists(path)) { + boost::filesystem::create_directory(path); + } + + if(path=="no_log") + { + LOG(INFO) << "... disabled dt logging ... turn it on if needed by setting value of [path_log]!"; + return; + } + + std::string fn_full = path + "/" + fn; + // first time create, then append; + std::ofstream ofs(fn_full.c_str(), std::ios_base::app | std::ios_base::out); + ofs << dt << "\n"; + ofs.close(); + +} + diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_gicp/gicp.h b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_gicp/gicp.h new file mode 100755 index 0000000..b91589a --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_gicp/gicp.h @@ -0,0 +1,443 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef MULTITHREADED_GICP_H_ +#define MULTITHREADED_GICP_H_ + +#include + +#include +#include +#include +#include +#include + +namespace pcl +{ +/** \brief GeneralizedIterativeClosestPoint is an ICP variant that implements + * the generalized iterative closest point algorithm as described by Alex Segal + * et al. in + * http://www.robots.ox.ac.uk/~avsegal/resources/papers/Generalized_ICP.pdf + * The approach is based on using anistropic cost functions to optimize the + * alignment after closest point assignments have been made. The original code + * uses GSL and ANN while in ours we use an eigen mapped BFGS and FLANN. \author + * Nizar Sallem \ingroup registration + */ +template +class MultithreadedGeneralizedIterativeClosestPoint : public GeneralizedIterativeClosestPoint +{ +public: + using IterativeClosestPoint::reg_name_; + using IterativeClosestPoint::getClassName; + using IterativeClosestPoint::indices_; + using IterativeClosestPoint::target_; + using IterativeClosestPoint::input_; + using IterativeClosestPoint::tree_; + using IterativeClosestPoint::tree_reciprocal_; + using IterativeClosestPoint::nr_iterations_; + using IterativeClosestPoint::max_iterations_; + using IterativeClosestPoint::previous_transformation_; + using IterativeClosestPoint::final_transformation_; + using IterativeClosestPoint::transformation_; + using IterativeClosestPoint::transformation_epsilon_; + using IterativeClosestPoint::converged_; + using IterativeClosestPoint::corr_dist_threshold_; + using IterativeClosestPoint::inlier_threshold_; + using IterativeClosestPoint::min_number_correspondences_; + using IterativeClosestPoint::update_visualizer_; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + typedef std::vector> MatricesVector; + typedef boost::shared_ptr MatricesVectorPtr; + typedef boost::shared_ptr MatricesVectorConstPtr; + + typedef typename Registration::KdTree InputKdTree; + typedef typename Registration::KdTreePtr InputKdTreePtr; + + typedef boost::shared_ptr> Ptr; + typedef boost::shared_ptr> ConstPtr; + + typedef Eigen::Matrix Vector6d; + + /** \brief Empty constructor. */ + MultithreadedGeneralizedIterativeClosestPoint() + : k_correspondences_(20) + , k_enable_timing_output_(false) + , reclculate_cov_normal_point_clouds_(false) + , recompute_target_cov_(false) + , recompute_source_cov(false) + , k_num_threads_(1) + , gicp_epsilon_(0.001) + , rotation_epsilon_(2e-3) + , mahalanobis_(0) + , max_inner_iterations_(20) + { + min_number_correspondences_ = 4; + reg_name_ = "MultithreadedGeneralizedIterativeClosestPoint"; + max_iterations_ = 200; + transformation_epsilon_ = 5e-4; + corr_dist_threshold_ = 5.; + // rigid_transformation_estimation_ = boost::bind( + // &MultithreadedGeneralizedIterativeClosestPoint::estimateRigidTransformationBFGS, this, + // _1, _2, _3, _4, _5); + + rigid_transformation_estimation_ = [this] (const PointCloudSource& cloud_src, + const std::vector& indices_src, + const PointCloudTarget& cloud_tgt, + const std::vector& indices_tgt, + Eigen::Matrix4f& transformation_matrix) + { + estimateRigidTransformationBFGS (cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix); + }; + + + + setNumThreads(k_num_threads_); + } + + void setNumThreads(int num_threads) + { + assert(num_threads > 0); + k_num_threads_ = num_threads; + omp_set_num_threads(k_num_threads_); + } + + void enableTimingOutput(bool enable) + { + k_enable_timing_output_ = enable; + } + + // template + // static GeneralizedIterativeClosestPoint + // MultithreadedGeneralizedIterativeClosestPoint () + + /** \brief Provide a pointer to the input dataset + * \param cloud the const boost shared pointer to a PointCloud message + */ + // PCL_DEPRECATED( + // "[pcl::registration::MultithreadedGeneralizedIterativeClosestPoint::" + // "setInputCloud] setInputCloud is deprecated. Please use setInputSource " + // "instead.") + void setInputCloud(const PointCloudSourceConstPtr& cloud); + + /** \brief Provide a pointer to the input dataset + * \param cloud the const boost shared pointer to a PointCloud message + */ + inline void setInputSource(const PointCloudSourceConstPtr& cloud) + { + if (cloud->points.empty()) + { + PCL_ERROR( + "[pcl::%s::setInputSource] Invalid or empty point cloud " + "dataset given!\n", + getClassName().c_str()); + return; + } + PointCloudSource input = *cloud; + // Set all the point.data[3] values to 1 to aid the rigid transformation + for (size_t i = 0; i < input.size(); ++i) + input[i].data[3] = 1.0; + + pcl::IterativeClosestPoint::setInputSource(cloud); + input_covariances_.reset(); + } + + /** \brief Provide a pointer to the covariances of the input source (if + * computed externally!). If not set, GeneralizedIterativeClosestPoint will + * compute the covariances itself. Make sure to set the covariances AFTER + * setting the input source point cloud (setting the input source point cloud + * will reset the covariances). \param[in] target the input point cloud target + */ + inline void setSourceCovariances(const MatricesVectorPtr& covariances) + { + input_covariances_ = covariances; + } + + /** \brief Provide a pointer to the input target (e.g., the point cloud that + * we want to align the input source to) \param[in] target the input point + * cloud target + */ + inline void setInputTarget(const PointCloudTargetConstPtr& target) + { + pcl::IterativeClosestPoint::setInputTarget(target); + target_covariances_.reset(); + } + + /** \brief Provide a pointer to the covariances of the input target (if + * computed externally!). If not set, GeneralizedIterativeClosestPoint will + * compute the covariances itself. Make sure to set the covariances AFTER + * setting the input source point cloud (setting the input source point cloud + * will reset the covariances). \param[in] target the input point cloud target + */ + inline void setTargetCovariances(const MatricesVectorPtr& covariances) + { + target_covariances_ = covariances; + } + + /** \brief Estimate a rigid rotation transformation between a source and a + * target point cloud using an iterative non-linear Levenberg-Marquardt + * approach. \param[in] cloud_src the source point cloud dataset \param[in] + * indices_src the vector of indices describing the points of interest in \a + * cloud_src \param[in] cloud_tgt the target point cloud dataset \param[in] + * indices_tgt the vector of indices describing the correspondences of the + * interst points from \a indices_src \param[out] transformation_matrix the + * resultant transformation matrix + */ + void estimateRigidTransformationBFGS(const PointCloudSource& cloud_src, const std::vector& indices_src, + const PointCloudTarget& cloud_tgt, const std::vector& indices_tgt, + Eigen::Matrix4f& transformation_matrix); + + /** \brief \return Mahalanobis distance matrix for the given point index */ + inline const Eigen::Matrix3d& mahalanobis(size_t index) const + { + assert(index < mahalanobis_.size()); + return mahalanobis_[index]; + } + + /** \brief Computes rotation matrix derivative. + * rotation matrix is obtainded from rotation angles x[3], x[4] and x[5] + * \return d/d_rx, d/d_ry and d/d_rz respectively in g[3], g[4] and g[5] + * param x array representing 3D transformation + * param R rotation matrix + * param g gradient vector + */ + void computeRDerivative(const Vector6d& x, const Eigen::Matrix3d& R, Vector6d& g) const; + + /** \brief Set the rotation epsilon (maximum allowable difference between two + * consecutive rotations) in order for an optimization to be considered as + * having converged to the final solution. \param epsilon the rotation epsilon + */ + inline void setRotationEpsilon(double epsilon) + { + rotation_epsilon_ = epsilon; + } + + /** \brief Get the rotation epsilon (maximum allowable difference between two + * consecutive rotations) as set by the user. + */ + inline double getRotationEpsilon() + { + return (rotation_epsilon_); + } + + /** \brief Set the number of neighbors used when selecting a point + * neighbourhood to compute covariances. A higher value will bring more + * accurate covariance matrix but will make covariances computation slower. + * \param k the number of neighbors to use when computing covariances + */ + void setCorrespondenceRandomness(int k) + { + k_correspondences_ = k; + } + + /** \brief Get the number of neighbors used when computing covariances as set + * by the user + */ + int getCorrespondenceRandomness() + { + return (k_correspondences_); + } + + /** set maximum number of iterations at the optimization step + * \param[in] max maximum number of iterations for the optimizer + */ + void setMaximumOptimizerIterations(int max) + { + max_inner_iterations_ = max; + } + + ///\return maximum number of iterations at the optimization step + int getMaximumOptimizerIterations() + { + return (max_inner_iterations_); + } + + void RecomputeTargetCovariance(bool recalculate) + { + recompute_target_cov_ = recalculate; + } + void RecomputeSourceCovariance(bool recalculate) + { + recompute_source_cov = recalculate; + } + +protected: + /** \brief The number of neighbors used for covariances computation. + * default: 20 + */ + int k_correspondences_; + + /** \brief The epsilon constant for gicp paper; this is NOT the convergence + * tolerence + * default: 0.001 + */ + double gicp_epsilon_; + + /** The epsilon constant for rotation error. (In GICP the transformation + * epsilon is split in rotation part and translation part). default: 2e-3 + */ + double rotation_epsilon_; + + /** \brief base transformation */ + Eigen::Matrix4f base_transformation_; + + /** \brief Temporary pointer to the source dataset. */ + const PointCloudSource* tmp_src_; + + /** \brief Temporary pointer to the target dataset. */ + const PointCloudTarget* tmp_tgt_; + + /** \brief Temporary pointer to the source dataset indices. */ + const std::vector* tmp_idx_src_; + + /** \brief Temporary pointer to the target dataset indices. */ + const std::vector* tmp_idx_tgt_; + + /** \brief Input cloud points covariances. */ + MatricesVectorPtr input_covariances_; + + /** \brief Target cloud points covariances. */ + MatricesVectorPtr target_covariances_; + + /** \brief Mahalanobis matrices holder. */ + std::vector mahalanobis_; + + /** \brief maximum number of optimizations */ + int max_inner_iterations_; + + /** \brief compute points covariances matrices according to the K nearest + * neighbors. K is set via setCorrespondenceRandomness() methode. + * \param cloud pointer to point cloud + * \param tree KD tree performer for nearest neighbors search + * \param[out] cloud_covariances covariances matrices for each point in the + * \param recompute recompute covariance matrices based on the inner algorithm + * cloud + */ + template + void computeCovariances(typename pcl::PointCloud::ConstPtr cloud, + const typename pcl::search::KdTree::Ptr tree, MatricesVector& cloud_covariances, + bool recompute = false); + + /** \return trace of mat1^t . mat2 + * \param mat1 matrix of dimension nxm + * \param mat2 matrix of dimension nxp + */ + inline double matricesInnerProd(const Eigen::MatrixXd& mat1, const Eigen::MatrixXd& mat2) const + { + double r = 0.; + size_t n = mat1.rows(); + // tr(mat1^t.mat2) + for (size_t i = 0; i < n; i++) + for (size_t j = 0; j < n; j++) + r += mat1(j, i) * mat2(i, j); + return r; + } + + /** \brief Rigid transformation computation method with initial guess. + * \param output the transformed input point cloud dataset using the rigid + * transformation found \param guess the initial guess of the transformation + * to compute + */ + void computeTransformation(PointCloudSource& output, const Eigen::Matrix4f& guess); + + /** \brief Search for the closest nearest neighbor of a given point. + * \param query the point to search a nearest neighbour for + * \param index vector of size 1 to store the index of the nearest neighbour + * found \param distance vector of size 1 to store the distance to nearest + * neighbour found + */ + inline bool searchForNeighbors(const PointSource& query, std::vector& index, std::vector& distance) + { + int k = tree_->nearestKSearch(query, 1, index, distance); + if (k == 0) + return (false); + return (true); + } + + /// \brief compute transformation matrix from transformation matrix + void applyState(Eigen::Matrix4f& t, const Vector6d& x) const; + + /// \brief optimization functor structure + struct OptimizationFunctorWithIndices : public BFGSDummyFunctor + { + OptimizationFunctorWithIndices(const MultithreadedGeneralizedIterativeClosestPoint* gicp) + : BFGSDummyFunctor(), gicp_(gicp) + { + } + double operator()(const Vector6d& x); + void df(const Vector6d& x, Vector6d& df); + void fdf(const Vector6d& x, double& f, Vector6d& df); + + const MultithreadedGeneralizedIterativeClosestPoint* gicp_; + }; + +// boost::function + std::function& cloud_src, const std::vector& src_indices, + const pcl::PointCloud& cloud_tgt, const std::vector& tgt_indices, + Eigen::Matrix4f& transformation_matrix)> + rigid_transformation_estimation_; + +private: + /** \brief Number of threads that GICP is allowed to use. */ + int k_num_threads_; + + /** \brief Enables log print statements with GICP timing information. */ + bool k_enable_timing_output_; + + bool reclculate_cov_normal_point_clouds_; + + bool recompute_target_cov_; + bool recompute_source_cov; +}; +} // namespace pcl + +#include + +#endif //#ifndef MULTITHREADED_GICP_H_ diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_gicp/gicp.hpp b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_gicp/gicp.hpp new file mode 100755 index 0000000..2b955cd --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_gicp/gicp.hpp @@ -0,0 +1,635 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef IMPL_MULTITHREADED_GICP_HPP_ +#define IMPL_MULTITHREADEd_GICP_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template +void pcl::MultithreadedGeneralizedIterativeClosestPoint + :: + setInputCloud( + const typename pcl::MultithreadedGeneralizedIterativeClosestPoint< + PointSource, + PointTarget>::PointCloudSourceConstPtr& cloud) { + setInputSource(cloud); +} + +//////////////////////////////////////////////////////////////////////////////////////// +template +template +void pcl::MultithreadedGeneralizedIterativeClosestPoint:: + computeCovariances(typename pcl::PointCloud::ConstPtr cloud, + const typename pcl::search::KdTree::Ptr kdtree, + MatricesVector& cloud_covariances, + bool recompute) { + if (k_correspondences_ > int(cloud->size())) { + PCL_ERROR("[pcl::MultithreadedGeneralizedIterativeClosestPoint::" + "computeCovariances] Number or points in cloud (%lu) is less " + "than k_correspondences_ (%lu)!\n", + cloud->size(), + k_correspondences_); + return; + } + + if (std::is_same::value and !recompute) { + CalculateCovarianceFromNormals(cloud, cloud_covariances, k_num_threads_); + } else { + // TODO cloud->points.size() vs cloud->size() ? any difference? + if (cloud_covariances.size() < cloud->size()) { + cloud_covariances.resize(cloud->size()); + } + + int enable_omp = (1 < k_num_threads_); +#pragma omp parallel for schedule(dynamic, 1) if (enable_omp) + for (int i = 0; i < cloud->points.size(); i++) { + if (k_enable_timing_output_) { + if (0 == i) { + // ROS_INFO_STREAM("Using " << omp_get_num_threads() << " threads"); + } + } + + Eigen::Vector3d mean; + std::vector nn_indices(k_correspondences_); + std::vector nn_dist_sq(k_correspondences_); + const PointT& query_point = cloud->points[i]; + Eigen::Matrix3d& cov = cloud_covariances[i]; + // Zero out the cov and mean + cov.setZero(); + mean.setZero(); + + // Search for the K nearest neighbours + kdtree->nearestKSearch( + query_point, k_correspondences_, nn_indices, nn_dist_sq); + + // Find the covariance matrix + for (int j = 0; j < k_correspondences_; j++) { + const PointT& pt = (*cloud)[nn_indices[j]]; + + mean[0] += pt.x; + mean[1] += pt.y; + mean[2] += pt.z; + + cov(0, 0) += pt.x * pt.x; + + cov(1, 0) += pt.y * pt.x; + cov(1, 1) += pt.y * pt.y; + + cov(2, 0) += pt.z * pt.x; + cov(2, 1) += pt.z * pt.y; + cov(2, 2) += pt.z * pt.z; + } + + mean /= static_cast(k_correspondences_); + // Get the actual covariance + for (int k = 0; k < 3; k++) { + for (int l = 0; l <= k; l++) { + cov(k, l) /= static_cast(k_correspondences_); + cov(k, l) -= mean[k] * mean[l]; + cov(l, k) = cov(k, l); + } + } + + // Compute the SVD (covariance matrix is symmetric so U = V') + Eigen::JacobiSVD svd(cov, Eigen::ComputeFullU); + cov.setZero(); + Eigen::Matrix3d U = svd.matrixU(); + + // Reconstitute the covariance matrix with modified singular values using + // the column // vectors in V. + for (int k = 0; k < 3; k++) { + Eigen::Vector3d col = U.col(k); + double v = 1.; // biggest 2 singular values replaced by 1 + if (k == 2) { // smallest singular value replaced by gicp_epsilon + v = gicp_epsilon_; + } + cov += v * col * col.transpose(); + } + } + } +} + +//////////////////////////////////////////////////////////////////////////////////////// +template +void pcl::MultithreadedGeneralizedIterativeClosestPoint< + PointSource, + PointTarget>::computeRDerivative(const Vector6d& x, + const Eigen::Matrix3d& R, + Vector6d& g) const { + Eigen::Matrix3d dR_dPhi; + Eigen::Matrix3d dR_dTheta; + Eigen::Matrix3d dR_dPsi; + + double phi = x[3], theta = x[4], psi = x[5]; + + double cphi = cos(phi), sphi = sin(phi); + double ctheta = cos(theta), stheta = sin(theta); + double cpsi = cos(psi), spsi = sin(psi); + + dR_dPhi(0, 0) = 0.; + dR_dPhi(1, 0) = 0.; + dR_dPhi(2, 0) = 0.; + + dR_dPhi(0, 1) = sphi * spsi + cphi * cpsi * stheta; + dR_dPhi(1, 1) = -cpsi * sphi + cphi * spsi * stheta; + dR_dPhi(2, 1) = cphi * ctheta; + + dR_dPhi(0, 2) = cphi * spsi - cpsi * sphi * stheta; + dR_dPhi(1, 2) = -cphi * cpsi - sphi * spsi * stheta; + dR_dPhi(2, 2) = -ctheta * sphi; + + dR_dTheta(0, 0) = -cpsi * stheta; + dR_dTheta(1, 0) = -spsi * stheta; + dR_dTheta(2, 0) = -ctheta; + + dR_dTheta(0, 1) = cpsi * ctheta * sphi; + dR_dTheta(1, 1) = ctheta * sphi * spsi; + dR_dTheta(2, 1) = -sphi * stheta; + + dR_dTheta(0, 2) = cphi * cpsi * ctheta; + dR_dTheta(1, 2) = cphi * ctheta * spsi; + dR_dTheta(2, 2) = -cphi * stheta; + + dR_dPsi(0, 0) = -ctheta * spsi; + dR_dPsi(1, 0) = cpsi * ctheta; + dR_dPsi(2, 0) = 0.; + + dR_dPsi(0, 1) = -cphi * cpsi - sphi * spsi * stheta; + dR_dPsi(1, 1) = -cphi * spsi + cpsi * sphi * stheta; + dR_dPsi(2, 1) = 0.; + + dR_dPsi(0, 2) = cpsi * sphi - cphi * spsi * stheta; + dR_dPsi(1, 2) = sphi * spsi + cphi * cpsi * stheta; + dR_dPsi(2, 2) = 0.; + + g[3] = matricesInnerProd(dR_dPhi, R); + g[4] = matricesInnerProd(dR_dTheta, R); + g[5] = matricesInnerProd(dR_dPsi, R); +} + +//////////////////////////////////////////////////////////////////////////////////////// +template +void pcl::MultithreadedGeneralizedIterativeClosestPoint:: + estimateRigidTransformationBFGS(const PointCloudSource& cloud_src, + const std::vector& indices_src, + const PointCloudTarget& cloud_tgt, + const std::vector& indices_tgt, + Eigen::Matrix4f& transformation_matrix) { + if (indices_src.size() < 4) { // need at least 4 samples + PCL_THROW_EXCEPTION( + NotEnoughPointsException, + "[pcl::MultithreadedGeneralizedIterativeClosestPoint::" + "estimateRigidTransformationBFGS] Need at least 4 points to estimate a " + "transform! Source and target have " + << indices_src.size() << " points!"); + return; + } + // Set the initial solution + Vector6d x = Vector6d::Zero(); + x[0] = transformation_matrix(0, 3); + x[1] = transformation_matrix(1, 3); + x[2] = transformation_matrix(2, 3); + x[3] = atan2(transformation_matrix(2, 1), transformation_matrix(2, 2)); + x[4] = asin(-transformation_matrix(2, 0)); + x[5] = atan2(transformation_matrix(1, 0), transformation_matrix(0, 0)); + + // Set temporary pointers + tmp_src_ = &cloud_src; + tmp_tgt_ = &cloud_tgt; + tmp_idx_src_ = &indices_src; + tmp_idx_tgt_ = &indices_tgt; + + // Optimize using forward-difference approximation LM + const double gradient_tol = 1e-2; + OptimizationFunctorWithIndices functor(this); + BFGS bfgs(functor); + bfgs.parameters.sigma = 0.01; + bfgs.parameters.rho = 0.01; + bfgs.parameters.tau1 = 9; + bfgs.parameters.tau2 = 0.05; + bfgs.parameters.tau3 = 0.5; + bfgs.parameters.order = 3; + + int inner_iterations_ = 0; + int result = bfgs.minimizeInit(x); + result = BFGSSpace::Running; + do { + inner_iterations_++; + result = bfgs.minimizeOneStep(x); + if (result) { + break; + } + result = bfgs.testGradient(gradient_tol); + } while (result == BFGSSpace::Running && + inner_iterations_ < max_inner_iterations_); + if (result == BFGSSpace::NoProgress || result == BFGSSpace::Success || + inner_iterations_ == max_inner_iterations_) { + PCL_DEBUG("[pcl::registration::TransformationEstimationBFGS::" + "estimateRigidTransformation]"); + PCL_DEBUG("BFGS solver finished with exit code %i \n", result); + transformation_matrix.setIdentity(); + applyState(transformation_matrix, x); + } else { + PCL_THROW_EXCEPTION( + SolverDidntConvergeException, + "[pcl::" + << getClassName() + << "::TransformationEstimationBFGS::estimateRigidTransformation] " + "BFGS solver didn't converge!"); + } +} + +//////////////////////////////////////////////////////////////////////////////////////// +template +inline double +pcl::MultithreadedGeneralizedIterativeClosestPoint:: + OptimizationFunctorWithIndices::operator()(const Vector6d& x) { + Eigen::Matrix4f transformation_matrix = gicp_->base_transformation_; + gicp_->applyState(transformation_matrix, x); + double f = 0; + int m = static_cast(gicp_->tmp_idx_src_->size()); + for (int i = 0; i < m; ++i) { + // The last coordinate, p_src[3] is guaranteed to be set to 1.0 in + // registration.hpp + Vector4fMapConst p_src = + gicp_->tmp_src_->points[(*gicp_->tmp_idx_src_)[i]].getVector4fMap(); + // The last coordinate, p_tgt[3] is guaranteed to be set to 1.0 in + // registration.hpp + Vector4fMapConst p_tgt = + gicp_->tmp_tgt_->points[(*gicp_->tmp_idx_tgt_)[i]].getVector4fMap(); + Eigen::Vector4f pp(transformation_matrix * p_src); + // Estimate the distance (cost function) + // The last coordiante is still guaranteed to be set to 1.0 + Eigen::Vector3d res(pp[0] - p_tgt[0], pp[1] - p_tgt[1], pp[2] - p_tgt[2]); + Eigen::Vector3d temp(gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]) * res); + // increment= res'*temp/num_matches = temp'*M*temp/num_matches (we postpone + // 1/num_matches after the loop closes) + f += double(res.transpose() * temp); + } + return f / m; +} + +//////////////////////////////////////////////////////////////////////////////////////// +template +inline void +pcl::MultithreadedGeneralizedIterativeClosestPoint:: + OptimizationFunctorWithIndices::df(const Vector6d& x, Vector6d& g) { + Eigen::Matrix4f transformation_matrix = gicp_->base_transformation_; + gicp_->applyState(transformation_matrix, x); + // Zero out g + g.setZero(); + // Eigen::Vector3d g_t = g.head<3> (); + Eigen::Matrix3d R = Eigen::Matrix3d::Zero(); + int m = static_cast(gicp_->tmp_idx_src_->size()); + for (int i = 0; i < m; ++i) { + // The last coordinate, p_src[3] is guaranteed to be set to 1.0 in + // registration.hpp + Vector4fMapConst p_src = + gicp_->tmp_src_->points[(*gicp_->tmp_idx_src_)[i]].getVector4fMap(); + // The last coordinate, p_tgt[3] is guaranteed to be set to 1.0 in + // registration.hpp + Vector4fMapConst p_tgt = + gicp_->tmp_tgt_->points[(*gicp_->tmp_idx_tgt_)[i]].getVector4fMap(); + + Eigen::Vector4f pp(transformation_matrix * p_src); + // The last coordiante is still guaranteed to be set to 1.0 + Eigen::Vector3d res(pp[0] - p_tgt[0], pp[1] - p_tgt[1], pp[2] - p_tgt[2]); + // temp = M*res + Eigen::Vector3d temp(gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]) * res); + // Increment translation gradient + // g.head<3> ()+= 2*M*res/num_matches (we postpone 2/num_matches after the + // loop closes) + g.head<3>() += temp; + // Increment rotation gradient + pp = gicp_->base_transformation_ * p_src; + Eigen::Vector3d p_src3(pp[0], pp[1], pp[2]); + R += p_src3 * temp.transpose(); + } + g.head<3>() *= 2.0 / m; + R *= 2.0 / m; + gicp_->computeRDerivative(x, R, g); +} + +//////////////////////////////////////////////////////////////////////////////////////// +template +inline void +pcl::MultithreadedGeneralizedIterativeClosestPoint:: + OptimizationFunctorWithIndices::fdf(const Vector6d& x, + double& f, + Vector6d& g) { + Eigen::Matrix4f transformation_matrix = gicp_->base_transformation_; + gicp_->applyState(transformation_matrix, x); + f = 0; + g.setZero(); + Eigen::Matrix3d R = Eigen::Matrix3d::Zero(); + const int m = static_cast(gicp_->tmp_idx_src_->size()); + for (int i = 0; i < m; ++i) { + // The last coordinate, p_src[3] is guaranteed to be set to 1.0 in + // registration.hpp + Vector4fMapConst p_src = + gicp_->tmp_src_->points[(*gicp_->tmp_idx_src_)[i]].getVector4fMap(); + // The last coordinate, p_tgt[3] is guaranteed to be set to 1.0 in + // registration.hpp + Vector4fMapConst p_tgt = + gicp_->tmp_tgt_->points[(*gicp_->tmp_idx_tgt_)[i]].getVector4fMap(); + Eigen::Vector4f pp(transformation_matrix * p_src); + // The last coordiante is still guaranteed to be set to 1.0 + Eigen::Vector3d res(pp[0] - p_tgt[0], pp[1] - p_tgt[1], pp[2] - p_tgt[2]); + // temp = M*res + Eigen::Vector3d temp(gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]) * res); + // Increment total error + f += double(res.transpose() * temp); + // Increment translation gradient + // g.head<3> ()+= 2*M*res/num_matches (we postpone 2/num_matches after the + // loop closes) + g.head<3>() += temp; + pp = gicp_->base_transformation_ * p_src; + Eigen::Vector3d p_src3(pp[0], pp[1], pp[2]); + // Increment rotation gradient + R += p_src3 * temp.transpose(); + } + f /= double(m); + g.head<3>() *= double(2.0 / m); + R *= 2.0 / m; + gicp_->computeRDerivative(x, R, g); +} + +//////////////////////////////////////////////////////////////////////////////////////// +template +inline void +pcl::MultithreadedGeneralizedIterativeClosestPoint:: + computeTransformation(PointCloudSource& output, + const Eigen::Matrix4f& guess) { + auto start_gicp = std::chrono::steady_clock::now(); + + pcl::IterativeClosestPoint::initComputeReciprocal(); + using namespace std; + // Difference between consecutive transforms + // Get the size of the target + const size_t N = indices_->size(); + // Set the mahalanobis matrices to identity + mahalanobis_.resize(N, Eigen::Matrix3d::Identity()); + + // Compute target cloud covariance matrices + auto start_covariances = std::chrono::steady_clock::now(); + if ((!target_covariances_) || (target_covariances_->empty())) { + target_covariances_.reset(new MatricesVector); + computeCovariances( + target_, tree_, *target_covariances_, recompute_target_cov_); + } + // Compute input cloud covariance matrices + if ((!input_covariances_) || (input_covariances_->empty())) { + input_covariances_.reset(new MatricesVector); + computeCovariances( + input_, tree_reciprocal_, *input_covariances_, recompute_source_cov); + } + auto end_covariances = std::chrono::steady_clock::now(); + + base_transformation_ = Eigen::Matrix4f::Identity(); + nr_iterations_ = 0; + converged_ = false; + double dist_threshold = corr_dist_threshold_ * corr_dist_threshold_; + + pcl::transformPointCloud(output, output, guess); + + double delta = 0.; + + auto start_iterations = std::chrono::steady_clock::now(); + while (!converged_) { + std::vector source_indices(indices_->size(), -1); + std::vector target_indices(indices_->size(), -1); + + // guess corresponds to base_t and transformation_ to t + Eigen::Matrix4d transform_R = Eigen::Matrix4d::Zero(); + for (size_t i = 0; i < 4; i++) { + for (size_t j = 0; j < 4; j++) { + for (size_t k = 0; k < 4; k++) { + transform_R(i, j) += + double(transformation_(i, k)) * double(guess(k, j)); + } + } + } + + const Eigen::Matrix3d R = transform_R.topLeftCorner<3, 3>(); + int failure = 0; + auto start_lookups = std::chrono::steady_clock::now(); + int enable_omp = (1 < k_num_threads_); +#pragma omp parallel for schedule(dynamic, 1) if (enable_omp) + for (size_t i = 0; i < N; i++) { + std::vector nn_indices(1); + std::vector nn_dists(1); + PointSource query = output[i]; + query.getVector4fMap() = transformation_ * query.getVector4fMap(); + + if (!searchForNeighbors(query, nn_indices, nn_dists)) { + PCL_ERROR( + "[pcl::%s::computeTransformation] Unable to find a nearest " + "neighbor in the target dataset for point %d in the source!\n", + getClassName().c_str(), + (*indices_)[i]); + failure = 1; + continue; + } + + // Check if the distance to the nearest neighbor is smaller than the user + // imposed threshold + if (nn_dists[0] < dist_threshold) { + Eigen::Matrix3d& C1 = (*input_covariances_)[i]; + Eigen::Matrix3d& C2 = (*target_covariances_)[nn_indices[0]]; + Eigen::Matrix3d& M = mahalanobis_[i]; + // M = R*C1 + M = R * C1; + // temp = M*R' + C2 = R*C1*R' + C2 + Eigen::Matrix3d temp = M * R.transpose(); + temp += C2; + // M = temp^-1 + M = temp.inverse(); + + source_indices[i] = static_cast(i); + target_indices[i] = nn_indices[0]; + } + } + auto end_lookups = std::chrono::steady_clock::now(); + + // There used to be a return statement inside of the loop that was + // incompatible with OpenMP Moving the failure and return logic outside of + // the loop + if (failure) { + return; + } + + // Resize to the actual number of valid correspondences + source_indices.erase( + std::remove(source_indices.begin(), source_indices.end(), -1), + source_indices.end()); + target_indices.erase( + std::remove(target_indices.begin(), target_indices.end(), -1), + target_indices.end()); + + /* optimize transformation using the current assignment and Mahalanobis + * metrics*/ + previous_transformation_ = transformation_; + + // optimization right here + auto start_optimization = std::chrono::steady_clock::now(); + try { + rigid_transformation_estimation_( + output, source_indices, *target_, target_indices, transformation_); + /* compute the delta from this iteration */ + delta = 0.; + for (int k = 0; k < 4; k++) { + for (int l = 0; l < 4; l++) { + double ratio = 1; + if (k < 3 && l < 3) { // rotation part of the transform + ratio = 1. / rotation_epsilon_; + } else { + ratio = 1. / transformation_epsilon_; + } + double c_delta = ratio * + fabs(previous_transformation_(k, l) - transformation_(k, l)); + if (c_delta > delta) { + delta = c_delta; + } + } + } + } catch (PCLException& e) { + PCL_DEBUG("[pcl::%s::computeTransformation] Optimization issue %s\n", + getClassName().c_str(), + e.what()); + break; + } + auto end_optimization = std::chrono::steady_clock::now(); + double lookups_time = + static_cast( + std::chrono::duration_cast(end_lookups - + start_lookups) + .count()) * + 1.0e-6; + double optimization_time = + static_cast( + std::chrono::duration_cast( + end_optimization - start_optimization) + .count()) * + 1.0e-6; + // ROS_INFO_STREAM("Lookups: " << lookups_time << " Optimization: " << + // optimization_time); + + nr_iterations_++; + // Check for convergence + if (nr_iterations_ >= max_iterations_ || delta < 1) { + converged_ = true; + previous_transformation_ = transformation_; + PCL_DEBUG( + "[pcl::%s::computeTransformation] Convergence reached. Number of " + "iterations: %d out of %d. Transformation difference: %f\n", + getClassName().c_str(), + nr_iterations_, + max_iterations_, + (transformation_ - previous_transformation_).array().abs().sum()); + } else { + PCL_DEBUG("[pcl::%s::computeTransformation] Convergence failed\n", + getClassName().c_str()); + } + } + auto end_iterations = std::chrono::steady_clock::now(); + + final_transformation_ = previous_transformation_ * guess; + + // Transform the point cloud + pcl::transformPointCloud(*input_, output, final_transformation_); + + auto end_gicp = std::chrono::steady_clock::now(); + if (k_enable_timing_output_) { + double iteration_time = + static_cast( + std::chrono::duration_cast( + end_iterations - start_iterations) + .count()) * + 1.0e-6; + double covariance_time = + static_cast( + std::chrono::duration_cast( + end_covariances - start_covariances) + .count()) * + 1.0e-6; + double total_time = + static_cast( + std::chrono::duration_cast(end_gicp - + start_gicp) + .count()) * + 1.0e-6; + // TODO(JN) Structured logging? ros topic? add info about the clouds? Remove + // ROS logs from GICP? + // ROS_DEBUG_STREAM("NrThreads: " << k_num_threads_ << " Total: " << total_time + // << " " + // << " Iteration: " << iteration_time + // << " Covariances: " << covariance_time + // << " NrIterations: " << nr_iterations_ + // << " Delta " << delta); + } +} + +template +void pcl::MultithreadedGeneralizedIterativeClosestPoint< + PointSource, + PointTarget>::applyState(Eigen::Matrix4f& t, const Vector6d& x) const { + // !!! CAUTION Stanford GICP uses the Z Y X euler angles convention + Eigen::Matrix3f R; + R = Eigen::AngleAxisf(static_cast(x[5]), Eigen::Vector3f::UnitZ()) * + Eigen::AngleAxisf(static_cast(x[4]), Eigen::Vector3f::UnitY()) * + Eigen::AngleAxisf(static_cast(x[3]), Eigen::Vector3f::UnitX()); + t.topLeftCorner<3, 3>().matrix() = R * t.topLeftCorner<3, 3>().matrix(); + Eigen::Vector4f T(static_cast(x[0]), + static_cast(x[1]), + static_cast(x[2]), + 0.0f); + t.col(3) += T; +} + +#endif // IMPL_MULTITHREADED_GICP_HPP_ diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/ndt_omp.h b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/ndt_omp.h new file mode 100755 index 0000000..1b7ad49 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/ndt_omp.h @@ -0,0 +1,537 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_NDT_OMP_H_ +#define PCL_REGISTRATION_NDT_OMP_H_ + +#include +#include +#include + +#include + +namespace pclomp { +enum NeighborSearchMethod { KDTREE, DIRECT26, DIRECT7, DIRECT1 }; + +/** \brief A 3D Normal Distribution Transform registration implementation for + * point cloud data. \note For more information please see Magnusson, M. + * (2009). The Three-Dimensional Normal-Distributions Transform — an Efficient + * Representation for Registration, Surface Analysis, and Loop Detection. PhD + * thesis, Orebro University. Orebro Studies in Technology 36., More, J., + * and Thuente, D. (1994). Line Search Algorithm with Guaranteed Sufficient + * Decrease In ACM Transactions on Mathematical Software. and Sun, W. and + * Yuan, Y, (2006) Optimization Theory and Methods: Nonlinear Programming. + * 89-100 \note Math refactored by Todor Stoyanov. \author Brian Okorn (Space + * and Naval Warfare Systems Center Pacific) + */ +template +class NormalDistributionsTransform + : public pcl::Registration { +protected: + typedef typename pcl::Registration::PointCloudSource + PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef typename pcl::Registration::PointCloudTarget + PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef pcl::PointIndices::Ptr PointIndicesPtr; + typedef pcl::PointIndices::ConstPtr PointIndicesConstPtr; + + /** \brief Typename of searchable voxel grid containing mean and covariance. + */ + typedef pclomp::VoxelGridCovariance TargetGrid; + /** \brief Typename of pointer to searchable voxel grid. */ + typedef TargetGrid* TargetGridPtr; + /** \brief Typename of const pointer to searchable voxel grid. */ + typedef const TargetGrid* TargetGridConstPtr; + /** \brief Typename of const pointer to searchable voxel grid leaf. */ + typedef typename TargetGrid::LeafConstPtr TargetGridLeafConstPtr; + +public: + typedef boost::shared_ptr< + NormalDistributionsTransform> + Ptr; + typedef boost::shared_ptr< + const NormalDistributionsTransform> + ConstPtr; + + /** \brief Constructor. + * Sets \ref outlier_ratio_ to 0.35, \ref step_size_ to 0.05 and \ref + * resolution_ to 1.0 + */ + NormalDistributionsTransform(); + + /** \brief Empty destructor */ + virtual ~NormalDistributionsTransform() {} + + void setNumThreads(int n) { + num_threads_ = n; + } + + /** \brief Provide a pointer to the input target (e.g., the point cloud that + * we want to align the input source to). \param[in] cloud the input point + * cloud target + */ + inline void setInputTarget(const PointCloudTargetConstPtr& cloud) { + pcl::Registration::setInputTarget(cloud); + init(); + } + + /** \brief Set/change the voxel grid resolution. + * \param[in] resolution side length of voxels + */ + inline void setResolution(float resolution) { + // Prevents unnessary voxel initiations + if (resolution_ != resolution) { + resolution_ = resolution; + if (input_) + init(); + } + } + + /** \brief Get voxel grid resolution. + * \return side length of voxels + */ + inline float getResolution() const { + return (resolution_); + } + + /** \brief Get the newton line search maximum step length. + * \return maximum step length + */ + inline double getStepSize() const { + return (step_size_); + } + + /** \brief Set/change the newton line search maximum step length. + * \param[in] step_size maximum step length + */ + inline void setStepSize(double step_size) { + step_size_ = step_size; + } + + /** \brief Get the point cloud outlier ratio. + * \return outlier ratio + */ + inline double getOulierRatio() const { + return (outlier_ratio_); + } + + /** \brief Set/change the point cloud outlier ratio. + * \param[in] outlier_ratio outlier ratio + */ + inline void setOulierRatio(double outlier_ratio) { + outlier_ratio_ = outlier_ratio; + } + + inline void setNeighborhoodSearchMethod(NeighborSearchMethod method) { + search_method = method; + } + + /** \brief Get the registration alignment probability. + * \return transformation probability + */ + inline double getTransformationProbability() const { + return (trans_probability_); + } + + /** \brief Get the number of iterations required to calculate alignment. + * \return final number of iterations + */ + inline int getFinalNumIteration() const { + return (nr_iterations_); + } + + /** \brief Convert 6 element transformation vector to affine transformation. + * \param[in] x transformation vector of the form [x, y, z, roll, pitch, yaw] + * \param[out] trans affine transform corresponding to given transfomation + * vector + */ + static void convertTransform(const Eigen::Matrix& x, + Eigen::Affine3f& trans) { + trans = + Eigen::Translation(float(x(0)), float(x(1)), float(x(2))) * + Eigen::AngleAxis(float(x(3)), Eigen::Vector3f::UnitX()) * + Eigen::AngleAxis(float(x(4)), Eigen::Vector3f::UnitY()) * + Eigen::AngleAxis(float(x(5)), Eigen::Vector3f::UnitZ()); + } + + /** \brief Convert 6 element transformation vector to transformation matrix. + * \param[in] x transformation vector of the form [x, y, z, roll, pitch, yaw] + * \param[out] trans 4x4 transformation matrix corresponding to given + * transfomation vector + */ + static void convertTransform(const Eigen::Matrix& x, + Eigen::Matrix4f& trans) { + Eigen::Affine3f _affine; + convertTransform(x, _affine); + trans = _affine.matrix(); + } + + // negative log likelihood function + // lower is better + double calculateScore(const PointCloudSource& cloud) const; + + // TODO: the functionality it's not yet implemented, it's just for the sake of + // interface + void enableTimingOutput(bool enable) { + k_enable_timing_output_ = enable; + } + +protected: + using pcl::Registration::reg_name_; + using pcl::Registration::getClassName; + using pcl::Registration::input_; + using pcl::Registration::indices_; + using pcl::Registration::target_; + using pcl::Registration::nr_iterations_; + using pcl::Registration::max_iterations_; + using pcl::Registration::previous_transformation_; + using pcl::Registration::final_transformation_; + using pcl::Registration::transformation_; + using pcl::Registration::transformation_epsilon_; + using pcl::Registration::converged_; + using pcl::Registration::corr_dist_threshold_; + using pcl::Registration::inlier_threshold_; + + using pcl::Registration::update_visualizer_; + + /** \brief Estimate the transformation and returns the transformed source + * (input) as output. \param[out] output the resultant input transfomed point + * cloud dataset + */ + virtual void computeTransformation(PointCloudSource& output) { + computeTransformation(output, Eigen::Matrix4f::Identity()); + } + + /** \brief Estimate the transformation and returns the transformed source + * (input) as output. \param[out] output the resultant input transfomed point + * cloud dataset \param[in] guess the initial gross estimation of the + * transformation + */ + virtual void computeTransformation(PointCloudSource& output, + const Eigen::Matrix4f& guess); + + /** \brief Initiate covariance voxel structure. */ + void inline init() { + target_cells_.setLeafSize(resolution_, resolution_, resolution_); + target_cells_.setInputCloud(target_); + // Initiate voxel structure. + target_cells_.filter(true); + } + + /** \brief Compute derivatives of probability function w.r.t. the + * transformation vector. \note Equation 6.10, 6.12 and 6.13 [Magnusson 2009]. + * \param[out] score_gradient the gradient vector of the probability function + * w.r.t. the transformation vector \param[out] hessian the hessian matrix of + * the probability function w.r.t. the transformation vector \param[in] + * trans_cloud transformed point cloud \param[in] p the current transform + * vector \param[in] compute_hessian flag to calculate hessian, unnessissary + * for step calculation. + */ + double computeDerivatives(Eigen::Matrix& score_gradient, + Eigen::Matrix& hessian, + PointCloudSource& trans_cloud, + Eigen::Matrix& p, + bool compute_hessian = true); + + /** \brief Compute individual point contirbutions to derivatives of + * probability function w.r.t. the transformation vector. \note + * Equation 6.10, 6.12 and 6.13 [Magnusson 2009]. \param[in,out] + * score_gradient the gradient vector of the probability function w.r.t. the + * transformation vector \param[in,out] hessian the hessian matrix of the + * probability function w.r.t. the transformation vector \param[in] x_trans + * transformed point minus mean of occupied covariance voxel \param[in] c_inv + * covariance of occupied covariance voxel \param[in] compute_hessian flag to + * calculate hessian, unnessissary for step calculation. + */ + double updateDerivatives(Eigen::Matrix& score_gradient, + Eigen::Matrix& hessian, + const Eigen::Matrix& point_gradient_, + const Eigen::Matrix& point_hessian_, + const Eigen::Vector3d& x_trans, + const Eigen::Matrix3d& c_inv, + bool compute_hessian = true) const; + + /** \brief Precompute anglular components of derivatives. + * \note Equation 6.19 and 6.21 [Magnusson 2009]. + * \param[in] p the current transform vector + * \param[in] compute_hessian flag to calculate hessian, unnessissary for step + * calculation. + */ + void computeAngleDerivatives(Eigen::Matrix& p, + bool compute_hessian = true); + + /** \brief Compute point derivatives. + * \note Equation 6.18-21 [Magnusson 2009]. + * \param[in] x point from the input cloud + * \param[in] compute_hessian flag to calculate hessian, unnessissary for step + * calculation. + */ + void computePointDerivatives(Eigen::Vector3d& x, + Eigen::Matrix& point_gradient_, + Eigen::Matrix& point_hessian_, + bool compute_hessian = true) const; + + void computePointDerivatives(Eigen::Vector3d& x, + Eigen::Matrix& point_gradient_, + Eigen::Matrix& point_hessian_, + bool compute_hessian = true) const; + + /** \brief Compute hessian of probability function w.r.t. the transformation + * vector. \note Equation 6.13 [Magnusson 2009]. \param[out] hessian the + * hessian matrix of the probability function w.r.t. the transformation vector + * \param[in] trans_cloud transformed point cloud + * \param[in] p the current transform vector + */ + void computeHessian(Eigen::Matrix& hessian, + PointCloudSource& trans_cloud, + Eigen::Matrix& p); + + /** \brief Compute individual point contirbutions to hessian of probability + * function w.r.t. the transformation vector. \note Equation 6.13 [Magnusson + * 2009]. \param[in,out] hessian the hessian matrix of the probability + * function w.r.t. the transformation vector \param[in] x_trans transformed + * point minus mean of occupied covariance voxel \param[in] c_inv covariance + * of occupied covariance voxel + */ + void updateHessian(Eigen::Matrix& hessian, + const Eigen::Matrix& point_gradient_, + const Eigen::Matrix& point_hessian_, + const Eigen::Vector3d& x_trans, + const Eigen::Matrix3d& c_inv) const; + + /** \brief Compute line search step length and update transform and + * probability derivatives using More-Thuente method. \note Search Algorithm + * [More, Thuente 1994] \param[in] x initial transformation vector, \f$ x \f$ + * in Equation 1.3 (Moore, Thuente 1994) and \f$ \vec{p} \f$ in Algorithm 2 + * [Magnusson 2009] \param[in] step_dir descent direction, \f$ p \f$ in + * Equation 1.3 (Moore, Thuente 1994) and \f$ \delta \vec{p} \f$ normalized in + * Algorithm 2 [Magnusson 2009] \param[in] step_init initial step length + * estimate, \f$ \alpha_0 \f$ in Moore-Thuente (1994) and the noramal of \f$ + * \delta \vec{p} \f$ in Algorithm 2 [Magnusson 2009] \param[in] step_max + * maximum step length, \f$ \alpha_max \f$ in Moore-Thuente (1994) \param[in] + * step_min minimum step length, \f$ \alpha_min \f$ in Moore-Thuente (1994) + * \param[out] score final score function value, \f$ f(x + \alpha p) \f$ in + * Equation 1.3 (Moore, Thuente 1994) and \f$ score \f$ in Algorithm 2 + * [Magnusson 2009] \param[in,out] score_gradient gradient of score function + * w.r.t. transformation vector, \f$ f'(x + \alpha p) \f$ in Moore-Thuente + * (1994) and \f$ \vec{g} \f$ in Algorithm 2 [Magnusson 2009] \param[out] + * hessian hessian of score function w.r.t. transformation vector, \f$ f''(x + + * \alpha p) \f$ in Moore-Thuente (1994) and \f$ H \f$ in Algorithm 2 + * [Magnusson 2009] \param[in,out] trans_cloud transformed point cloud, \f$ X + * \f$ transformed by \f$ T(\vec{p},\vec{x}) \f$ in Algorithm 2 [Magnusson + * 2009] \return final step length + */ + double computeStepLengthMT(const Eigen::Matrix& x, + Eigen::Matrix& step_dir, + double step_init, + double step_max, + double step_min, + double& score, + Eigen::Matrix& score_gradient, + Eigen::Matrix& hessian, + PointCloudSource& trans_cloud); + + /** \brief Update interval of possible step lengths for More-Thuente method, + * \f$ I \f$ in More-Thuente (1994) \note Updating Algorithm until some value + * satifies \f$ \psi(\alpha_k) \leq 0 \f$ and \f$ \phi'(\alpha_k) \geq 0 \f$ + * and Modified Updating Algorithm from then on [More, Thuente 1994]. + * \param[in,out] a_l first endpoint of interval \f$ I \f$, \f$ \alpha_l \f$ + * in Moore-Thuente (1994) \param[in,out] f_l value at first endpoint, \f$ f_l + * \f$ in Moore-Thuente (1994), \f$ \psi(\alpha_l) \f$ for Update Algorithm + * and \f$ \phi(\alpha_l) \f$ for Modified Update Algorithm \param[in,out] g_l + * derivative at first endpoint, \f$ g_l \f$ in Moore-Thuente (1994), \f$ + * \psi'(\alpha_l) \f$ for Update Algorithm and \f$ \phi'(\alpha_l) \f$ for + * Modified Update Algorithm \param[in,out] a_u second endpoint of interval + * \f$ I \f$, \f$ \alpha_u \f$ in Moore-Thuente (1994) \param[in,out] f_u + * value at second endpoint, \f$ f_u \f$ in Moore-Thuente (1994), \f$ + * \psi(\alpha_u) \f$ for Update Algorithm and \f$ \phi(\alpha_u) \f$ for + * Modified Update Algorithm \param[in,out] g_u derivative at second endpoint, + * \f$ g_u \f$ in Moore-Thuente (1994), \f$ \psi'(\alpha_u) \f$ for Update + * Algorithm and \f$ \phi'(\alpha_u) \f$ for Modified Update Algorithm + * \param[in] a_t trial value, \f$ \alpha_t \f$ in Moore-Thuente (1994) + * \param[in] f_t value at trial value, \f$ f_t \f$ in Moore-Thuente (1994), + * \f$ \psi(\alpha_t) \f$ for Update Algorithm and \f$ \phi(\alpha_t) \f$ for + * Modified Update Algorithm \param[in] g_t derivative at trial value, \f$ g_t + * \f$ in Moore-Thuente (1994), \f$ \psi'(\alpha_t) \f$ for Update Algorithm + * and \f$ \phi'(\alpha_t) \f$ for Modified Update Algorithm \return if + * interval converges + */ + bool updateIntervalMT(double& a_l, + double& f_l, + double& g_l, + double& a_u, + double& f_u, + double& g_u, + double a_t, + double f_t, + double g_t); + + /** \brief Select new trial value for More-Thuente method. + * \note Trial Value Selection [More, Thuente 1994], \f$ \psi(\alpha_k) \f$ is + * used for \f$ f_k \f$ and \f$ g_k \f$ until some value satifies the test \f$ + * \psi(\alpha_k) \leq 0 \f$ and \f$ \phi'(\alpha_k) \geq 0 \f$ then \f$ + * \phi(\alpha_k) \f$ is used from then on. \note Interpolation Minimizer + * equations from Optimization Theory and Methods: Nonlinear Programming By + * Wenyu Sun, Ya-xiang Yuan (89-100). \param[in] a_l first endpoint of + * interval \f$ I \f$, \f$ \alpha_l \f$ in Moore-Thuente (1994) \param[in] f_l + * value at first endpoint, \f$ f_l \f$ in Moore-Thuente (1994) \param[in] g_l + * derivative at first endpoint, \f$ g_l \f$ in Moore-Thuente (1994) + * \param[in] a_u second endpoint of interval \f$ I \f$, \f$ \alpha_u \f$ in + * Moore-Thuente (1994) \param[in] f_u value at second endpoint, \f$ f_u \f$ + * in Moore-Thuente (1994) \param[in] g_u derivative at second endpoint, \f$ + * g_u \f$ in Moore-Thuente (1994) \param[in] a_t previous trial value, \f$ + * \alpha_t \f$ in Moore-Thuente (1994) \param[in] f_t value at previous trial + * value, \f$ f_t \f$ in Moore-Thuente (1994) \param[in] g_t derivative at + * previous trial value, \f$ g_t \f$ in Moore-Thuente (1994) \return new trial + * value + */ + double trialValueSelectionMT(double a_l, + double f_l, + double g_l, + double a_u, + double f_u, + double g_u, + double a_t, + double f_t, + double g_t); + + /** \brief Auxilary function used to determin endpoints of More-Thuente + * interval. \note \f$ \psi(\alpha) \f$ in Equation 1.6 (Moore, Thuente 1994) + * \param[in] a the step length, \f$ \alpha \f$ in More-Thuente (1994) + * \param[in] f_a function value at step length a, \f$ \phi(\alpha) \f$ in + * More-Thuente (1994) \param[in] f_0 initial function value, \f$ \phi(0) \f$ + * in Moore-Thuente (1994) \param[in] g_0 initial function gradiant, \f$ + * \phi'(0) \f$ in More-Thuente (1994) \param[in] mu the step length, constant + * \f$ \mu \f$ in Equation 1.1 [More, Thuente 1994] \return sufficent decrease + * value + */ + inline double auxilaryFunction_PsiMT( + double a, double f_a, double f_0, double g_0, double mu = 1.e-4) { + return (f_a - f_0 - mu * g_0 * a); + } + + /** \brief Auxilary function derivative used to determin endpoints of + * More-Thuente interval. \note \f$ \psi'(\alpha) \f$, derivative of + * Equation 1.6 (Moore, Thuente 1994) \param[in] g_a function gradient at step + * length a, \f$ \phi'(\alpha) \f$ in More-Thuente (1994) \param[in] g_0 + * initial function gradiant, \f$ \phi'(0) \f$ in More-Thuente (1994) + * \param[in] mu the step length, constant \f$ \mu \f$ in Equation 1.1 [More, + * Thuente 1994] \return sufficent decrease derivative + */ + inline double + auxilaryFunction_dPsiMT(double g_a, double g_0, double mu = 1.e-4) { + return (g_a - mu * g_0); + } + + /** \brief The voxel grid generated from target cloud containing point means + * and covariances. */ + TargetGrid target_cells_; + + // double fitness_epsilon_; + + /** \brief The side length of voxels. */ + float resolution_; + + /** \brief The maximum step length. */ + double step_size_; + + /** \brief The ratio of outliers of points w.r.t. a normal distribution, + * Equation 6.7 [Magnusson 2009]. */ + double outlier_ratio_; + + /** \brief The normalization constants used fit the point distribution to a + * normal distribution, Equation 6.8 [Magnusson 2009]. */ + double gauss_d1_, gauss_d2_, gauss_d3_; + + /** \brief The probability score of the transform applied to the input cloud, + * Equation 6.9 and 6.10 [Magnusson 2009]. */ + double trans_probability_; + + /** \brief Precomputed Angular Gradient + * + * The precomputed angular derivatives for the jacobian of a transformation + * vector, Equation 6.19 [Magnusson 2009]. + */ + Eigen::Vector3d j_ang_a_, j_ang_b_, j_ang_c_, j_ang_d_, j_ang_e_, j_ang_f_, + j_ang_g_, j_ang_h_; + + Eigen::Matrix j_ang; + + /** \brief Precomputed Angular Hessian + * + * The precomputed angular derivatives for the hessian of a transformation + * vector, Equation 6.19 [Magnusson 2009]. + */ + Eigen::Vector3d h_ang_a2_, h_ang_a3_, h_ang_b2_, h_ang_b3_, h_ang_c2_, + h_ang_c3_, h_ang_d1_, h_ang_d2_, h_ang_d3_, h_ang_e1_, h_ang_e2_, + h_ang_e3_, h_ang_f1_, h_ang_f2_, h_ang_f3_; + + Eigen::Matrix h_ang; + + /** \brief The first order derivative of the transformation of a point w.r.t. + * the transform vector, \f$ J_E \f$ in Equation 6.18 [Magnusson 2009]. */ + // Eigen::Matrix point_gradient_; + + /** \brief The second order derivative of the transformation of a point w.r.t. + * the transform vector, \f$ H_E \f$ in Equation 6.20 [Magnusson 2009]. */ + // Eigen::Matrix point_hessian_; + + int num_threads_; + + /** \brief Enables log print statements with GICP timing information. */ + bool k_enable_timing_output_; + +public: + NeighborSearchMethod search_method; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace pclomp + +#include +#include +#endif // PCL_REGISTRATION_NDT_H_ diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/ndt_omp_impl.hpp b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/ndt_omp_impl.hpp new file mode 100755 index 0000000..7fb11f7 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/ndt_omp_impl.hpp @@ -0,0 +1,1121 @@ + +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_NDT_OMP_IMPL_H_ +#define PCL_REGISTRATION_NDT_OMP_IMPL_H_ + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pclomp::NormalDistributionsTransform:: + NormalDistributionsTransform() + : target_cells_(), + resolution_(1.0f), + step_size_(0.1), + outlier_ratio_(0.55), + gauss_d1_(), + gauss_d2_(), + gauss_d3_(), + trans_probability_(), + j_ang_a_(), + j_ang_b_(), + j_ang_c_(), + j_ang_d_(), + j_ang_e_(), + j_ang_f_(), + j_ang_g_(), + j_ang_h_(), + h_ang_a2_(), + h_ang_a3_(), + h_ang_b2_(), + h_ang_b3_(), + h_ang_c2_(), + h_ang_c3_(), + h_ang_d1_(), + h_ang_d2_(), + h_ang_d3_(), + h_ang_e1_(), + h_ang_e2_(), + h_ang_e3_(), + h_ang_f1_(), + h_ang_f2_(), + h_ang_f3_() { + reg_name_ = "NormalDistributionsTransform"; + + double gauss_c1, gauss_c2; + + // Initializes the guassian fitting parameters (eq. 6.8) [Magnusson 2009] + gauss_c1 = 10.0 * (1 - outlier_ratio_); + gauss_c2 = outlier_ratio_ / pow(resolution_, 3); + gauss_d3_ = -log(gauss_c2); + gauss_d1_ = -log(gauss_c1 + gauss_c2) - gauss_d3_; + gauss_d2_ = + -2 * log((-log(gauss_c1 * exp(-0.5) + gauss_c2) - gauss_d3_) / gauss_d1_); + + transformation_epsilon_ = 0.1; + max_iterations_ = 35; + + search_method = KDTREE; + num_threads_ = omp_get_max_threads(); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void pclomp::NormalDistributionsTransform:: + computeTransformation(PointCloudSource& output, + const Eigen::Matrix4f& guess) { + nr_iterations_ = 0; + converged_ = false; + + double gauss_c1, gauss_c2; + + // Initializes the guassian fitting parameters (eq. 6.8) [Magnusson 2009] + gauss_c1 = 10 * (1 - outlier_ratio_); + gauss_c2 = outlier_ratio_ / pow(resolution_, 3); + gauss_d3_ = -log(gauss_c2); + gauss_d1_ = -log(gauss_c1 + gauss_c2) - gauss_d3_; + gauss_d2_ = + -2 * log((-log(gauss_c1 * exp(-0.5) + gauss_c2) - gauss_d3_) / gauss_d1_); + + if (guess != Eigen::Matrix4f::Identity()) { + // Initialise final transformation to the guessed one + final_transformation_ = guess; + // Apply guessed transformation prior to search for neighbours + transformPointCloud(output, output, guess); + } + + Eigen::Transform eig_transformation; + eig_transformation.matrix() = final_transformation_; + + // Convert initial guess matrix to 6 element transformation vector + Eigen::Matrix p, delta_p, score_gradient; + Eigen::Vector3f init_translation = eig_transformation.translation(); + Eigen::Vector3f init_rotation = + eig_transformation.rotation().eulerAngles(0, 1, 2); + p << init_translation(0), init_translation(1), init_translation(2), + init_rotation(0), init_rotation(1), init_rotation(2); + + Eigen::Matrix hessian; + + double score = 0; + double delta_p_norm; + + // Calculate derivates of initial transform vector, subsequent derivative + // calculations are done in the step length determination. + score = computeDerivatives(score_gradient, hessian, output, p); + + while (!converged_) { + // Store previous transformation + previous_transformation_ = transformation_; + + // Solve for decent direction using newton method, line 23 in Algorithm 2 + // [Magnusson 2009] + Eigen::JacobiSVD> sv( + hessian, Eigen::ComputeFullU | Eigen::ComputeFullV); + // Negative for maximization as opposed to minimization + delta_p = sv.solve(-score_gradient); + + // Calculate step length with guarnteed sufficient decrease [More, Thuente + // 1994] + delta_p_norm = delta_p.norm(); + + if (delta_p_norm == 0 || delta_p_norm != delta_p_norm) { + trans_probability_ = score / static_cast(input_->points.size()); + converged_ = delta_p_norm == delta_p_norm; + return; + } + + delta_p.normalize(); + delta_p_norm = computeStepLengthMT(p, + delta_p, + delta_p_norm, + step_size_, + transformation_epsilon_ / 2, + score, + score_gradient, + hessian, + output); + delta_p *= delta_p_norm; + + transformation_ = + (Eigen::Translation(static_cast(delta_p(0)), + static_cast(delta_p(1)), + static_cast(delta_p(2))) * + Eigen::AngleAxis(static_cast(delta_p(3)), + Eigen::Vector3f::UnitX()) * + Eigen::AngleAxis(static_cast(delta_p(4)), + Eigen::Vector3f::UnitY()) * + Eigen::AngleAxis(static_cast(delta_p(5)), + Eigen::Vector3f::UnitZ())) + .matrix(); + + p = p + delta_p; + + // Update Visualizer (untested) + if (update_visualizer_ != 0) + update_visualizer_( + output, std::vector(), *target_, std::vector()); + + if (nr_iterations_ > max_iterations_ || + (nr_iterations_ && + (std::fabs(delta_p_norm) < transformation_epsilon_))) { + converged_ = true; + } + + nr_iterations_++; + } + + // Store transformation probability. The realtive differences within each + // scan registration are accurate but the normalization constants need to be + // modified for it to be globally accurate + trans_probability_ = score / static_cast(input_->points.size()); +} + +#ifndef _OPENMP +int omp_get_max_threads() { + return 1; +} +int omp_get_thread_num() { + return 0; +} +#endif + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +double pclomp::NormalDistributionsTransform:: + computeDerivatives(Eigen::Matrix& score_gradient, + Eigen::Matrix& hessian, + PointCloudSource& trans_cloud, + Eigen::Matrix& p, + bool compute_hessian) { + score_gradient.setZero(); + hessian.setZero(); + double score = 0; + + std::vector scores(input_->points.size()); + std::vector, + Eigen::aligned_allocator>> + score_gradients(input_->points.size()); + std::vector, + Eigen::aligned_allocator>> + hessians(input_->points.size()); + for (int i = 0; i < input_->points.size(); i++) { + scores[i] = 0; + score_gradients[i].setZero(); + hessians[i].setZero(); + } + + // Precompute Angular Derivatives (eq. 6.19 and 6.21)[Magnusson 2009] + computeAngleDerivatives(p); + + std::vector> neighborhoods(num_threads_); + std::vector> distancess(num_threads_); + + // Update gradient and hessian for each point, line 17 in Algorithm 2 + // [Magnusson 2009] +#pragma omp parallel for num_threads(num_threads_) schedule(guided, 8) + for (int idx = 0; idx < input_->points.size(); idx++) { + int thread_n = omp_get_thread_num(); + + // Original Point and Transformed Point + PointSource x_pt, x_trans_pt; + // Original Point and Transformed Point (for math) + Eigen::Vector3d x, x_trans; + // Occupied Voxel + TargetGridLeafConstPtr cell; + // Inverse Covariance of Occupied Voxel + Eigen::Matrix3d c_inv; + + // Initialize Point Gradient and Hessian + Eigen::Matrix point_gradient_; + Eigen::Matrix point_hessian_; + point_gradient_.setZero(); + point_gradient_.block<3, 3>(0, 0).setIdentity(); + point_hessian_.setZero(); + + x_trans_pt = trans_cloud.points[idx]; + + auto& neighborhood = neighborhoods[thread_n]; + auto& distances = distancess[thread_n]; + + // Find nieghbors (Radius search has been experimentally faster than direct + // neighbor checking. + switch (search_method) { + case KDTREE: + target_cells_.radiusSearch( + x_trans_pt, resolution_, neighborhood, distances); + break; + case DIRECT26: + target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood); + break; + default: + case DIRECT7: + target_cells_.getNeighborhoodAtPoint7(x_trans_pt, neighborhood); + break; + case DIRECT1: + target_cells_.getNeighborhoodAtPoint1(x_trans_pt, neighborhood); + break; + } + + double score_pt = 0; + Eigen::Matrix score_gradient_pt = + Eigen::Matrix::Zero(); + Eigen::Matrix hessian_pt = + Eigen::Matrix::Zero(); + + for (typename std::vector::iterator + neighborhood_it = neighborhood.begin(); + neighborhood_it != neighborhood.end(); + neighborhood_it++) { + cell = *neighborhood_it; + x_pt = input_->points[idx]; + x = Eigen::Vector3d(x_pt.x, x_pt.y, x_pt.z); + + x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); + + // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009] + x_trans -= cell->getMean(); + // Uses precomputed covariance for speed. + c_inv = cell->getInverseCov(); + + // Compute derivative of transform function w.r.t. transform vector, J_E + // and H_E in Equations 6.18 and 6.20 [Magnusson 2009] + computePointDerivatives(x, point_gradient_, point_hessian_); + // Update score, gradient and hessian, lines 19-21 in Algorithm 2, + // according to Equations 6.10, 6.12 and 6.13, respectively [Magnusson + // 2009] + score_pt += updateDerivatives(score_gradient_pt, + hessian_pt, + point_gradient_, + point_hessian_, + x_trans, + c_inv, + compute_hessian); + } + + scores[idx] = score_pt; + score_gradients[idx].noalias() = score_gradient_pt; + hessians[idx].noalias() = hessian_pt; + } + + // Ensure that the result is invariant against the summing up order + for (int i = 0; i < input_->points.size(); i++) { + score += scores[i]; + score_gradient += score_gradients[i]; + hessian += hessians[i]; + } + + return (score); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void pclomp::NormalDistributionsTransform:: + computeAngleDerivatives(Eigen::Matrix& p, + bool compute_hessian) { + // Simplified math for near 0 angles + double cx, cy, cz, sx, sy, sz; + if (fabs(p(3)) < 10e-5) { + // p(3) = 0; + cx = 1.0; + sx = 0.0; + } else { + cx = cos(p(3)); + sx = sin(p(3)); + } + if (fabs(p(4)) < 10e-5) { + // p(4) = 0; + cy = 1.0; + sy = 0.0; + } else { + cy = cos(p(4)); + sy = sin(p(4)); + } + + if (fabs(p(5)) < 10e-5) { + // p(5) = 0; + cz = 1.0; + sz = 0.0; + } else { + cz = cos(p(5)); + sz = sin(p(5)); + } + + // Precomputed angular gradiant components. Letters correspond to + // Equation 6.19 [Magnusson 2009] + j_ang_a_ << (-sx * sz + cx * sy * cz), (-sx * cz - cx * sy * sz), (-cx * cy); + j_ang_b_ << (cx * sz + sx * sy * cz), (cx * cz - sx * sy * sz), (-sx * cy); + j_ang_c_ << (-sy * cz), sy * sz, cy; + j_ang_d_ << sx * cy * cz, (-sx * cy * sz), sx * sy; + j_ang_e_ << (-cx * cy * cz), cx * cy * sz, (-cx * sy); + j_ang_f_ << (-cy * sz), (-cy * cz), 0; + j_ang_g_ << (cx * cz - sx * sy * sz), (-cx * sz - sx * sy * cz), 0; + j_ang_h_ << (sx * cz + cx * sy * sz), (cx * sy * cz - sx * sz), 0; + + j_ang.setZero(); + j_ang.row(0).noalias() = Eigen::Vector4f( + (-sx * sz + cx * sy * cz), (-sx * cz - cx * sy * sz), (-cx * cy), 0.0f); + j_ang.row(1).noalias() = Eigen::Vector4f( + (cx * sz + sx * sy * cz), (cx * cz - sx * sy * sz), (-sx * cy), 0.0f); + j_ang.row(2).noalias() = Eigen::Vector4f((-sy * cz), sy * sz, cy, 0.0f); + j_ang.row(3).noalias() = + Eigen::Vector4f(sx * cy * cz, (-sx * cy * sz), sx * sy, 0.0f); + j_ang.row(4).noalias() = + Eigen::Vector4f((-cx * cy * cz), cx * cy * sz, (-cx * sy), 0.0f); + j_ang.row(5).noalias() = Eigen::Vector4f((-cy * sz), (-cy * cz), 0, 0.0f); + j_ang.row(6).noalias() = Eigen::Vector4f( + (cx * cz - sx * sy * sz), (-cx * sz - sx * sy * cz), 0, 0.0f); + j_ang.row(7).noalias() = Eigen::Vector4f( + (sx * cz + cx * sy * sz), (cx * sy * cz - sx * sz), 0, 0.0f); + + if (compute_hessian) { + // Precomputed angular hessian components. Letters correspond to + // Equation 6.21 and numbers correspond to row index [Magnusson 2009] + h_ang_a2_ << (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), sx * cy; + h_ang_a3_ << (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), + (-cx * cy); + + h_ang_b2_ << (cx * cy * cz), (-cx * cy * sz), (cx * sy); + h_ang_b3_ << (sx * cy * cz), (-sx * cy * sz), (sx * sy); + + h_ang_c2_ << (-sx * cz - cx * sy * sz), (sx * sz - cx * sy * cz), 0; + h_ang_c3_ << (cx * cz - sx * sy * sz), (-sx * sy * cz - cx * sz), 0; + + h_ang_d1_ << (-cy * cz), (cy * sz), (sy); + h_ang_d2_ << (-sx * sy * cz), (sx * sy * sz), (sx * cy); + h_ang_d3_ << (cx * sy * cz), (-cx * sy * sz), (-cx * cy); + + h_ang_e1_ << (sy * sz), (sy * cz), 0; + h_ang_e2_ << (-sx * cy * sz), (-sx * cy * cz), 0; + h_ang_e3_ << (cx * cy * sz), (cx * cy * cz), 0; + + h_ang_f1_ << (-cy * cz), (cy * sz), 0; + h_ang_f2_ << (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), 0; + h_ang_f3_ << (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), 0; + + h_ang.setZero(); + h_ang.row(0).noalias() = Eigen::Vector4f((-cx * sz - sx * sy * cz), + (-cx * cz + sx * sy * sz), + sx * cy, + 0.0f); // a2 + h_ang.row(1).noalias() = Eigen::Vector4f((-sx * sz + cx * sy * cz), + (-cx * sy * sz - sx * cz), + (-cx * cy), + 0.0f); // a3 + + h_ang.row(2).noalias() = + Eigen::Vector4f((cx * cy * cz), (-cx * cy * sz), (cx * sy), 0.0f); // b2 + h_ang.row(3).noalias() = + Eigen::Vector4f((sx * cy * cz), (-sx * cy * sz), (sx * sy), 0.0f); // b3 + + h_ang.row(4).noalias() = Eigen::Vector4f( + (-sx * cz - cx * sy * sz), (sx * sz - cx * sy * cz), 0, 0.0f); // c2 + h_ang.row(5).noalias() = Eigen::Vector4f( + (cx * cz - sx * sy * sz), (-sx * sy * cz - cx * sz), 0, 0.0f); // c3 + + h_ang.row(6).noalias() = + Eigen::Vector4f((-cy * cz), (cy * sz), (sy), 0.0f); // d1 + h_ang.row(7).noalias() = + Eigen::Vector4f((-sx * sy * cz), (sx * sy * sz), (sx * cy), 0.0f); // d2 + h_ang.row(8).noalias() = Eigen::Vector4f( + (cx * sy * cz), (-cx * sy * sz), (-cx * cy), 0.0f); // d3 + + h_ang.row(9).noalias() = + Eigen::Vector4f((sy * sz), (sy * cz), 0, 0.0f); // e1 + h_ang.row(10).noalias() = + Eigen::Vector4f((-sx * cy * sz), (-sx * cy * cz), 0, 0.0f); // e2 + h_ang.row(11).noalias() = + Eigen::Vector4f((cx * cy * sz), (cx * cy * cz), 0, 0.0f); // e3 + + h_ang.row(12).noalias() = + Eigen::Vector4f((-cy * cz), (cy * sz), 0, 0.0f); // f1 + h_ang.row(13).noalias() = Eigen::Vector4f( + (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), 0, 0.0f); // f2 + h_ang.row(14).noalias() = Eigen::Vector4f( + (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), 0, 0.0f); // f3 + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void pclomp::NormalDistributionsTransform:: + computePointDerivatives(Eigen::Vector3d& x, + Eigen::Matrix& point_gradient_, + Eigen::Matrix& point_hessian_, + bool compute_hessian) const { + Eigen::Vector4f x4(x[0], x[1], x[2], 0.0f); + + // Calculate first derivative of Transformation Equation 6.17 w.r.t. transform + // vector p. Derivative w.r.t. ith element of transform vector corresponds to + // column i, Equation 6.18 and 6.19 [Magnusson 2009] + Eigen::Matrix x_j_ang = j_ang * x4; + + point_gradient_(1, 3) = x_j_ang[0]; + point_gradient_(2, 3) = x_j_ang[1]; + point_gradient_(0, 4) = x_j_ang[2]; + point_gradient_(1, 4) = x_j_ang[3]; + point_gradient_(2, 4) = x_j_ang[4]; + point_gradient_(0, 5) = x_j_ang[5]; + point_gradient_(1, 5) = x_j_ang[6]; + point_gradient_(2, 5) = x_j_ang[7]; + + if (compute_hessian) { + Eigen::Matrix x_h_ang = h_ang * x4; + + // Vectors from Equation 6.21 [Magnusson 2009] + Eigen::Vector4f a(0, x_h_ang[0], x_h_ang[1], 0.0f); + Eigen::Vector4f b(0, x_h_ang[2], x_h_ang[3], 0.0f); + Eigen::Vector4f c(0, x_h_ang[4], x_h_ang[5], 0.0f); + Eigen::Vector4f d(x_h_ang[6], x_h_ang[7], x_h_ang[8], 0.0f); + Eigen::Vector4f e(x_h_ang[9], x_h_ang[10], x_h_ang[11], 0.0f); + Eigen::Vector4f f(x_h_ang[12], x_h_ang[13], x_h_ang[14], 0.0f); + + // Calculate second derivative of Transformation Equation 6.17 w.r.t. + // transform vector p. Derivative w.r.t. ith and jth elements of transform + // vector corresponds to the 3x1 block matrix starting at (3i,j), + // Equation 6.20 and 6.21 [Magnusson 2009] + point_hessian_.block<4, 1>((9 / 3) * 4, 3) = a; + point_hessian_.block<4, 1>((12 / 3) * 4, 3) = b; + point_hessian_.block<4, 1>((15 / 3) * 4, 3) = c; + point_hessian_.block<4, 1>((9 / 3) * 4, 4) = b; + point_hessian_.block<4, 1>((12 / 3) * 4, 4) = d; + point_hessian_.block<4, 1>((15 / 3) * 4, 4) = e; + point_hessian_.block<4, 1>((9 / 3) * 4, 5) = c; + point_hessian_.block<4, 1>((12 / 3) * 4, 5) = e; + point_hessian_.block<4, 1>((15 / 3) * 4, 5) = f; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void pclomp::NormalDistributionsTransform:: + computePointDerivatives(Eigen::Vector3d& x, + Eigen::Matrix& point_gradient_, + Eigen::Matrix& point_hessian_, + bool compute_hessian) const { + // Calculate first derivative of Transformation Equation 6.17 w.r.t. transform + // vector p. Derivative w.r.t. ith element of transform vector corresponds to + // column i, Equation 6.18 and 6.19 [Magnusson 2009] + point_gradient_(1, 3) = x.dot(j_ang_a_); + point_gradient_(2, 3) = x.dot(j_ang_b_); + point_gradient_(0, 4) = x.dot(j_ang_c_); + point_gradient_(1, 4) = x.dot(j_ang_d_); + point_gradient_(2, 4) = x.dot(j_ang_e_); + point_gradient_(0, 5) = x.dot(j_ang_f_); + point_gradient_(1, 5) = x.dot(j_ang_g_); + point_gradient_(2, 5) = x.dot(j_ang_h_); + + if (compute_hessian) { + // Vectors from Equation 6.21 [Magnusson 2009] + Eigen::Vector3d a, b, c, d, e, f; + + a << 0, x.dot(h_ang_a2_), x.dot(h_ang_a3_); + b << 0, x.dot(h_ang_b2_), x.dot(h_ang_b3_); + c << 0, x.dot(h_ang_c2_), x.dot(h_ang_c3_); + d << x.dot(h_ang_d1_), x.dot(h_ang_d2_), x.dot(h_ang_d3_); + e << x.dot(h_ang_e1_), x.dot(h_ang_e2_), x.dot(h_ang_e3_); + f << x.dot(h_ang_f1_), x.dot(h_ang_f2_), x.dot(h_ang_f3_); + + // Calculate second derivative of Transformation Equation 6.17 w.r.t. + // transform vector p. Derivative w.r.t. ith and jth elements of transform + // vector corresponds to the 3x1 block matrix starting at (3i,j), + // Equation 6.20 and 6.21 [Magnusson 2009] + point_hessian_.block<3, 1>(9, 3) = a; + point_hessian_.block<3, 1>(12, 3) = b; + point_hessian_.block<3, 1>(15, 3) = c; + point_hessian_.block<3, 1>(9, 4) = b; + point_hessian_.block<3, 1>(12, 4) = d; + point_hessian_.block<3, 1>(15, 4) = e; + point_hessian_.block<3, 1>(9, 5) = c; + point_hessian_.block<3, 1>(12, 5) = e; + point_hessian_.block<3, 1>(15, 5) = f; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +double pclomp::NormalDistributionsTransform:: + updateDerivatives(Eigen::Matrix& score_gradient, + Eigen::Matrix& hessian, + const Eigen::Matrix& point_gradient4, + const Eigen::Matrix& point_hessian_, + const Eigen::Vector3d& x_trans, + const Eigen::Matrix3d& c_inv, + bool compute_hessian) const { + Eigen::Matrix x_trans4(x_trans[0], x_trans[1], x_trans[2], 0.0f); + Eigen::Matrix4f c_inv4 = Eigen::Matrix4f::Zero(); + c_inv4.topLeftCorner(3, 3) = c_inv.cast(); + + float gauss_d2 = gauss_d2_; + + // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson + // 2009] + float e_x_cov_x = exp(-gauss_d2 * x_trans4.dot(x_trans4 * c_inv4) * 0.5f); + // Calculate probability of transtormed points existance, Equation 6.9 + // [Magnusson 2009] + float score_inc = -gauss_d1_ * e_x_cov_x; + + e_x_cov_x = gauss_d2 * e_x_cov_x; + + // Error checking for invalid values. + if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x) + return (0); + + // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009] + e_x_cov_x *= gauss_d1_; + + Eigen::Matrix c_inv4_x_point_gradient4 = + c_inv4 * point_gradient4; + Eigen::Matrix x_trans4_dot_c_inv4_x_point_gradient4 = + x_trans4 * c_inv4_x_point_gradient4; + + score_gradient.noalias() += + (e_x_cov_x * x_trans4_dot_c_inv4_x_point_gradient4).cast(); + + if (compute_hessian) { + Eigen::Matrix x_trans4_x_c_inv4 = x_trans4 * c_inv4; + Eigen::Matrix + point_gradient4_colj_dot_c_inv4_x_point_gradient4_col_i = + point_gradient4.transpose() * c_inv4_x_point_gradient4; + Eigen::Matrix x_trans4_dot_c_inv4_x_ext_point_hessian_4ij; + + for (int i = 0; i < 6; i++) { + // Sigma_k^-1 d(T(x,p))/dpi, Reusable portion of Equation 6.12 and 6.13 + // [Magnusson 2009] Update gradient, Equation 6.12 [Magnusson 2009] + x_trans4_dot_c_inv4_x_ext_point_hessian_4ij.noalias() = + x_trans4_x_c_inv4 * point_hessian_.block<4, 6>(i * 4, 0); + + for (int j = 0; j < hessian.cols(); j++) { + // Update hessian, Equation 6.13 [Magnusson 2009] + hessian(i, j) += e_x_cov_x * + (-gauss_d2 * x_trans4_dot_c_inv4_x_point_gradient4(i) * + x_trans4_dot_c_inv4_x_point_gradient4(j) + + x_trans4_dot_c_inv4_x_ext_point_hessian_4ij(j) + + point_gradient4_colj_dot_c_inv4_x_point_gradient4_col_i(j, i)); + } + } + } + + return (score_inc); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void pclomp::NormalDistributionsTransform:: + computeHessian(Eigen::Matrix& hessian, + PointCloudSource& trans_cloud, + Eigen::Matrix&) { + // Original Point and Transformed Point + PointSource x_pt, x_trans_pt; + // Original Point and Transformed Point (for math) + Eigen::Vector3d x, x_trans; + // Occupied Voxel + TargetGridLeafConstPtr cell; + // Inverse Covariance of Occupied Voxel + Eigen::Matrix3d c_inv; + + // Initialize Point Gradient and Hessian + Eigen::Matrix point_gradient_; + Eigen::Matrix point_hessian_; + point_gradient_.setZero(); + point_gradient_.block<3, 3>(0, 0).setIdentity(); + point_hessian_.setZero(); + + hessian.setZero(); + + // Precompute Angular Derivatives unessisary because only used after regular + // derivative calculation + + // Update hessian for each point, line 17 in Algorithm 2 [Magnusson 2009] + for (size_t idx = 0; idx < input_->points.size(); idx++) { + x_trans_pt = trans_cloud.points[idx]; + + // Find nieghbors (Radius search has been experimentally faster than direct + // neighbor checking. + std::vector neighborhood; + std::vector distances; + switch (search_method) { + case KDTREE: + target_cells_.radiusSearch( + x_trans_pt, resolution_, neighborhood, distances); + break; + case DIRECT26: + target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood); + break; + default: + case DIRECT7: + target_cells_.getNeighborhoodAtPoint7(x_trans_pt, neighborhood); + break; + case DIRECT1: + target_cells_.getNeighborhoodAtPoint1(x_trans_pt, neighborhood); + break; + } + + for (typename std::vector::iterator + neighborhood_it = neighborhood.begin(); + neighborhood_it != neighborhood.end(); + neighborhood_it++) { + cell = *neighborhood_it; + + { + x_pt = input_->points[idx]; + x = Eigen::Vector3d(x_pt.x, x_pt.y, x_pt.z); + + x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); + + // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009] + x_trans -= cell->getMean(); + // Uses precomputed covariance for speed. + c_inv = cell->getInverseCov(); + + // Compute derivative of transform function w.r.t. transform vector, J_E + // and H_E in Equations 6.18 and 6.20 [Magnusson 2009] + computePointDerivatives(x, point_gradient_, point_hessian_); + // Update hessian, lines 21 in Algorithm 2, according to + // Equations 6.10, 6.12 and 6.13, respectively [Magnusson 2009] + updateHessian(hessian, point_gradient_, point_hessian_, x_trans, c_inv); + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void pclomp::NormalDistributionsTransform:: + updateHessian(Eigen::Matrix& hessian, + const Eigen::Matrix& point_gradient_, + const Eigen::Matrix& point_hessian_, + const Eigen::Vector3d& x_trans, + const Eigen::Matrix3d& c_inv) const { + Eigen::Vector3d cov_dxd_pi; + // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson + // 2009] + double e_x_cov_x = + gauss_d2_ * exp(-gauss_d2_ * x_trans.dot(c_inv * x_trans) / 2); + + // Error checking for invalid values. + if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x) + return; + + // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009] + e_x_cov_x *= gauss_d1_; + + for (int i = 0; i < 6; i++) { + // Sigma_k^-1 d(T(x,p))/dpi, Reusable portion of Equation 6.12 and 6.13 + // [Magnusson 2009] + cov_dxd_pi = c_inv * point_gradient_.col(i); + + for (int j = 0; j < hessian.cols(); j++) { + // Update hessian, Equation 6.13 [Magnusson 2009] + hessian(i, j) += e_x_cov_x * + (-gauss_d2_ * x_trans.dot(cov_dxd_pi) * + x_trans.dot(c_inv * point_gradient_.col(j)) + + x_trans.dot(c_inv * point_hessian_.block<3, 1>(3 * i, j)) + + point_gradient_.col(j).dot(cov_dxd_pi)); + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +bool pclomp::NormalDistributionsTransform:: + updateIntervalMT(double& a_l, + double& f_l, + double& g_l, + double& a_u, + double& f_u, + double& g_u, + double a_t, + double f_t, + double g_t) { + // Case U1 in Update Algorithm and Case a in Modified Update Algorithm [More, + // Thuente 1994] + if (f_t > f_l) { + a_u = a_t; + f_u = f_t; + g_u = g_t; + return (false); + } + // Case U2 in Update Algorithm and Case b in Modified Update Algorithm [More, + // Thuente 1994] + else if (g_t * (a_l - a_t) > 0) { + a_l = a_t; + f_l = f_t; + g_l = g_t; + return (false); + } + // Case U3 in Update Algorithm and Case c in Modified Update Algorithm [More, + // Thuente 1994] + else if (g_t * (a_l - a_t) < 0) { + a_u = a_l; + f_u = f_l; + g_u = g_l; + + a_l = a_t; + f_l = f_t; + g_l = g_t; + return (false); + } + // Interval Converged + else + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +double pclomp::NormalDistributionsTransform:: + trialValueSelectionMT(double a_l, + double f_l, + double g_l, + double a_u, + double f_u, + double g_u, + double a_t, + double f_t, + double g_t) { + // Case 1 in Trial Value Selection [More, Thuente 1994] + if (f_t > f_l) { + // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and + // g_t Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; + double w = std::sqrt(z * z - g_t * g_l); + // Equation 2.4.56 [Sun, Yuan 2006] + double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); + + // Calculate the minimizer of the quadratic that interpolates f_l, f_t and + // g_l Equation 2.4.2 [Sun, Yuan 2006] + double a_q = + a_l - 0.5 * (a_l - a_t) * g_l / (g_l - (f_l - f_t) / (a_l - a_t)); + + if (std::fabs(a_c - a_l) < std::fabs(a_q - a_l)) + return (a_c); + else + return (0.5 * (a_q + a_c)); + } + // Case 2 in Trial Value Selection [More, Thuente 1994] + else if (g_t * g_l < 0) { + // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and + // g_t Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; + double w = std::sqrt(z * z - g_t * g_l); + // Equation 2.4.56 [Sun, Yuan 2006] + double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); + + // Calculate the minimizer of the quadratic that interpolates f_l, g_l and + // g_t Equation 2.4.5 [Sun, Yuan 2006] + double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l; + + if (std::fabs(a_c - a_t) >= std::fabs(a_s - a_t)) + return (a_c); + else + return (a_s); + } + // Case 3 in Trial Value Selection [More, Thuente 1994] + else if (std::fabs(g_t) <= std::fabs(g_l)) { + // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and + // g_t Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; + double w = std::sqrt(z * z - g_t * g_l); + double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); + + // Calculate the minimizer of the quadratic that interpolates g_l and g_t + // Equation 2.4.5 [Sun, Yuan 2006] + double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l; + + double a_t_next; + + if (std::fabs(a_c - a_t) < std::fabs(a_s - a_t)) + a_t_next = a_c; + else + a_t_next = a_s; + + if (a_t > a_l) + return (std::min(a_t + 0.66 * (a_u - a_t), a_t_next)); + else + return (std::max(a_t + 0.66 * (a_u - a_t), a_t_next)); + } + // Case 4 in Trial Value Selection [More, Thuente 1994] + else { + // Calculate the minimizer of the cubic that interpolates f_u, f_t, g_u and + // g_t Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_u) / (a_t - a_u) - g_t - g_u; + double w = std::sqrt(z * z - g_t * g_u); + // Equation 2.4.56 [Sun, Yuan 2006] + return (a_u + (a_t - a_u) * (w - g_u - z) / (g_t - g_u + 2 * w)); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +double pclomp::NormalDistributionsTransform:: + computeStepLengthMT(const Eigen::Matrix& x, + Eigen::Matrix& step_dir, + double step_init, + double step_max, + double step_min, + double& score, + Eigen::Matrix& score_gradient, + Eigen::Matrix& hessian, + PointCloudSource& trans_cloud) { + // Set the value of phi(0), Equation 1.3 [More, Thuente 1994] + double phi_0 = -score; + // Set the value of phi'(0), Equation 1.3 [More, Thuente 1994] + double d_phi_0 = -(score_gradient.dot(step_dir)); + + Eigen::Matrix x_t; + + if (d_phi_0 >= 0) { + // Not a decent direction + if (d_phi_0 == 0) + return 0; + else { + // Reverse step direction and calculate optimal step. + d_phi_0 *= -1; + step_dir *= -1; + } + } + + // The Search Algorithm for T(mu) [More, Thuente 1994] + + int max_step_iterations = 10; + int step_iterations = 0; + + // Sufficient decreace constant, Equation 1.1 [More, Thuete 1994] + double mu = 1.e-4; + // Curvature condition constant, Equation 1.2 [More, Thuete 1994] + double nu = 0.9; + + // Initial endpoints of Interval I, + double a_l = 0, a_u = 0; + + // Auxiliary function psi is used until I is determined ot be a closed + // interval, Equation 2.1 [More, Thuente 1994] + double f_l = auxilaryFunction_PsiMT(a_l, phi_0, phi_0, d_phi_0, mu); + double g_l = auxilaryFunction_dPsiMT(d_phi_0, d_phi_0, mu); + + double f_u = auxilaryFunction_PsiMT(a_u, phi_0, phi_0, d_phi_0, mu); + double g_u = auxilaryFunction_dPsiMT(d_phi_0, d_phi_0, mu); + + // Check used to allow More-Thuente step length calculation to be skipped by + // making step_min == step_max + bool interval_converged = (step_max - step_min) < 0, open_interval = true; + + double a_t = step_init; + a_t = std::min(a_t, step_max); + a_t = std::max(a_t, step_min); + + x_t = x + step_dir * a_t; + + final_transformation_ = + (Eigen::Translation(static_cast(x_t(0)), + static_cast(x_t(1)), + static_cast(x_t(2))) * + Eigen::AngleAxis(static_cast(x_t(3)), + Eigen::Vector3f::UnitX()) * + Eigen::AngleAxis(static_cast(x_t(4)), + Eigen::Vector3f::UnitY()) * + Eigen::AngleAxis(static_cast(x_t(5)), + Eigen::Vector3f::UnitZ())) + .matrix(); + + // New transformed point cloud + transformPointCloud(*input_, trans_cloud, final_transformation_); + + // Updates score, gradient and hessian. Hessian calculation is unessisary but + // testing showed that most step calculations use the initial step suggestion + // and recalculation the reusable portions of the hessian would intail more + // computation time. + score = computeDerivatives(score_gradient, hessian, trans_cloud, x_t, true); + + // Calculate phi(alpha_t) + double phi_t = -score; + // Calculate phi'(alpha_t) + double d_phi_t = -(score_gradient.dot(step_dir)); + + // Calculate psi(alpha_t) + double psi_t = auxilaryFunction_PsiMT(a_t, phi_t, phi_0, d_phi_0, mu); + // Calculate psi'(alpha_t) + double d_psi_t = auxilaryFunction_dPsiMT(d_phi_t, d_phi_0, mu); + + // Iterate until max number of iterations, interval convergance or a value + // satisfies the sufficient decrease, Equation 1.1, and curvature condition, + // Equation 1.2 [More, Thuente 1994] + while (!interval_converged && step_iterations < max_step_iterations && + !(psi_t <= 0 /*Sufficient Decrease*/ && + d_phi_t <= -nu * d_phi_0 /*Curvature Condition*/)) { + // Use auxilary function if interval I is not closed + if (open_interval) { + a_t = trialValueSelectionMT( + a_l, f_l, g_l, a_u, f_u, g_u, a_t, psi_t, d_psi_t); + } else { + a_t = trialValueSelectionMT( + a_l, f_l, g_l, a_u, f_u, g_u, a_t, phi_t, d_phi_t); + } + + a_t = std::min(a_t, step_max); + a_t = std::max(a_t, step_min); + + x_t = x + step_dir * a_t; + + final_transformation_ = + (Eigen::Translation(static_cast(x_t(0)), + static_cast(x_t(1)), + static_cast(x_t(2))) * + Eigen::AngleAxis(static_cast(x_t(3)), + Eigen::Vector3f::UnitX()) * + Eigen::AngleAxis(static_cast(x_t(4)), + Eigen::Vector3f::UnitY()) * + Eigen::AngleAxis(static_cast(x_t(5)), + Eigen::Vector3f::UnitZ())) + .matrix(); + + // New transformed point cloud + // Done on final cloud to prevent wasted computation + transformPointCloud(*input_, trans_cloud, final_transformation_); + + // Updates score, gradient. Values stored to prevent wasted computation. + score = + computeDerivatives(score_gradient, hessian, trans_cloud, x_t, false); + + // Calculate phi(alpha_t+) + phi_t = -score; + // Calculate phi'(alpha_t+) + d_phi_t = -(score_gradient.dot(step_dir)); + + // Calculate psi(alpha_t+) + psi_t = auxilaryFunction_PsiMT(a_t, phi_t, phi_0, d_phi_0, mu); + // Calculate psi'(alpha_t+) + d_psi_t = auxilaryFunction_dPsiMT(d_phi_t, d_phi_0, mu); + + // Check if I is now a closed interval + if (open_interval && (psi_t <= 0 && d_psi_t >= 0)) { + open_interval = false; + + // Converts f_l and g_l from psi to phi + f_l = f_l + phi_0 - mu * d_phi_0 * a_l; + g_l = g_l + mu * d_phi_0; + + // Converts f_u and g_u from psi to phi + f_u = f_u + phi_0 - mu * d_phi_0 * a_u; + g_u = g_u + mu * d_phi_0; + } + + if (open_interval) { + // Update interval end points using Updating Algorithm [More, Thuente + // 1994] + interval_converged = + updateIntervalMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, psi_t, d_psi_t); + } else { + // Update interval end points using Modified Updating Algorithm [More, + // Thuente 1994] + interval_converged = + updateIntervalMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, phi_t, d_phi_t); + } + + step_iterations++; + } + + // If inner loop was run then hessian needs to be calculated. + // Hessian is unnessisary for step length determination but gradients are + // required so derivative and transform data is stored for the next iteration. + if (step_iterations) + computeHessian(hessian, trans_cloud, x_t); + + return (a_t); +} + +template +double +pclomp::NormalDistributionsTransform::calculateScore( + const PointCloudSource& trans_cloud) const { + double score = 0; + + for (int idx = 0; idx < trans_cloud.points.size(); idx++) { + PointSource x_trans_pt = trans_cloud.points[idx]; + + // Find nieghbors (Radius search has been experimentally faster than direct + // neighbor checking. + std::vector neighborhood; + std::vector distances; + switch (search_method) { + case KDTREE: + target_cells_.radiusSearch( + x_trans_pt, resolution_, neighborhood, distances); + break; + case DIRECT26: + target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood); + break; + default: + case DIRECT7: + target_cells_.getNeighborhoodAtPoint7(x_trans_pt, neighborhood); + break; + case DIRECT1: + target_cells_.getNeighborhoodAtPoint1(x_trans_pt, neighborhood); + break; + } + + for (typename std::vector::iterator + neighborhood_it = neighborhood.begin(); + neighborhood_it != neighborhood.end(); + neighborhood_it++) { + TargetGridLeafConstPtr cell = *neighborhood_it; + + Eigen::Vector3d x_trans = + Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); + + // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009] + x_trans -= cell->getMean(); + // Uses precomputed covariance for speed. + Eigen::Matrix3d c_inv = cell->getInverseCov(); + + // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 + // [Magnusson 2009] + double e_x_cov_x = exp(-gauss_d2_ * x_trans.dot(c_inv * x_trans) / 2); + // Calculate probability of transtormed points existance, Equation 6.9 + // [Magnusson 2009] + double score_inc = -gauss_d1_ * e_x_cov_x - gauss_d3_; + + score += score_inc / neighborhood.size(); + } + } + return (score) / static_cast(trans_cloud.size()); +} + +#endif // PCL_REGISTRATION_NDT_IMPL_H_ diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/voxel_grid_covariance_omp.h b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/voxel_grid_covariance_omp.h new file mode 100755 index 0000000..96a9cf8 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/voxel_grid_covariance_omp.h @@ -0,0 +1,526 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VOXEL_GRID_COVARIANCE_OMP_H_ +#define PCL_VOXEL_GRID_COVARIANCE_OMP_H_ + +#include +#include +#include +#include +#include +#include + +namespace pclomp { +/** \brief A searchable voxel strucure containing the mean and covariance of the + * data. \note For more information please see Magnusson, M. (2009). The + * Three-Dimensional Normal-Distributions Transform — an Efficient Representation + * for Registration, Surface Analysis, and Loop Detection. PhD thesis, Orebro + * University. Orebro Studies in Technology 36 \author Brian Okorn (Space + * and Naval Warfare Systems Center Pacific) + */ +template +class VoxelGridCovariance : public pcl::VoxelGrid { +protected: + using pcl::VoxelGrid::filter_name_; + using pcl::VoxelGrid::getClassName; + using pcl::VoxelGrid::input_; + using pcl::VoxelGrid::indices_; + using pcl::VoxelGrid::filter_limit_negative_; + using pcl::VoxelGrid::filter_limit_min_; + using pcl::VoxelGrid::filter_limit_max_; + using pcl::VoxelGrid::filter_field_name_; + + using pcl::VoxelGrid::downsample_all_data_; + using pcl::VoxelGrid::leaf_layout_; + using pcl::VoxelGrid::save_leaf_layout_; + using pcl::VoxelGrid::leaf_size_; + using pcl::VoxelGrid::min_b_; + using pcl::VoxelGrid::max_b_; + using pcl::VoxelGrid::inverse_leaf_size_; + using pcl::VoxelGrid::div_b_; + using pcl::VoxelGrid::divb_mul_; + + typedef typename pcl::traits::fieldList::type FieldList; + typedef typename pcl::Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + +public: + typedef boost::shared_ptr> Ptr; + typedef boost::shared_ptr> ConstPtr; + + /** \brief Simple structure to hold a centroid, covarince and the number of + * points in a leaf. Inverse covariance, eigen vectors and engen values are + * precomputed. */ + struct Leaf { + /** \brief Constructor. + * Sets \ref nr_points, \ref icov_, \ref mean_ and \ref evals_ to 0 and \ref + * cov_ and \ref evecs_ to the identity matrix + */ + Leaf() + : nr_points(0), + mean_(Eigen::Vector3d::Zero()), + centroid(), + cov_(Eigen::Matrix3d::Identity()), + icov_(Eigen::Matrix3d::Zero()), + evecs_(Eigen::Matrix3d::Identity()), + evals_(Eigen::Vector3d::Zero()) {} + + /** \brief Get the voxel covariance. + * \return covariance matrix + */ + Eigen::Matrix3d getCov() const { + return (cov_); + } + + /** \brief Get the inverse of the voxel covariance. + * \return inverse covariance matrix + */ + Eigen::Matrix3d getInverseCov() const { + return (icov_); + } + + /** \brief Get the voxel centroid. + * \return centroid + */ + Eigen::Vector3d getMean() const { + return (mean_); + } + + /** \brief Get the eigen vectors of the voxel covariance. + * \note Order corresponds with \ref getEvals + * \return matrix whose columns contain eigen vectors + */ + Eigen::Matrix3d getEvecs() const { + return (evecs_); + } + + /** \brief Get the eigen values of the voxel covariance. + * \note Order corresponds with \ref getEvecs + * \return vector of eigen values + */ + Eigen::Vector3d getEvals() const { + return (evals_); + } + + /** \brief Get the number of points contained by this voxel. + * \return number of points + */ + int getPointCount() const { + return (nr_points); + } + + /** \brief Number of points contained by voxel */ + int nr_points; + + /** \brief 3D voxel centroid */ + Eigen::Vector3d mean_; + + /** \brief Nd voxel centroid + * \note Differs from \ref mean_ when color data is used + */ + Eigen::VectorXf centroid; + + /** \brief Voxel covariance matrix */ + Eigen::Matrix3d cov_; + + /** \brief Inverse of voxel covariance matrix */ + Eigen::Matrix3d icov_; + + /** \brief Eigen vectors of voxel covariance matrix */ + Eigen::Matrix3d evecs_; + + /** \brief Eigen values of voxel covariance matrix */ + Eigen::Vector3d evals_; + }; + + /** \brief Pointer to VoxelGridCovariance leaf structure */ + typedef Leaf* LeafPtr; + + /** \brief Const pointer to VoxelGridCovariance leaf structure */ + typedef const Leaf* LeafConstPtr; + + typedef std::map Map; + +public: + /** \brief Constructor. + * Sets \ref leaf_size_ to 0 and \ref searchable_ to false. + */ + VoxelGridCovariance() + : searchable_(true), + min_points_per_voxel_(6), + min_covar_eigvalue_mult_(0.01), + leaves_(), + voxel_centroids_(), + voxel_centroids_leaf_indices_(), + kdtree_() { + downsample_all_data_ = false; + save_leaf_layout_ = false; + leaf_size_.setZero(); + min_b_.setZero(); + max_b_.setZero(); + filter_name_ = "VoxelGridCovariance"; + } + + /** \brief Set the minimum number of points required for a cell to be used + * (must be 3 or greater for covariance calculation). \param[in] + * min_points_per_voxel the minimum number of points for required for a voxel + * to be used + */ + inline void setMinPointPerVoxel(int min_points_per_voxel) { + if (min_points_per_voxel > 2) { + min_points_per_voxel_ = min_points_per_voxel; + } else { + PCL_WARN("%s: Covariance calculation requires at least 3 points, setting " + "Min Point per Voxel to 3 ", + this->getClassName().c_str()); + min_points_per_voxel_ = 3; + } + } + + /** \brief Get the minimum number of points required for a cell to be used. + * \return the minimum number of points for required for a voxel to be used + */ + inline int getMinPointPerVoxel() { + return min_points_per_voxel_; + } + + /** \brief Set the minimum allowable ratio between eigenvalues to prevent + * singular covariance matrices. \param[in] min_covar_eigvalue_mult the + * minimum allowable ratio between eigenvalues + */ + inline void setCovEigValueInflationRatio(double min_covar_eigvalue_mult) { + min_covar_eigvalue_mult_ = min_covar_eigvalue_mult; + } + + /** \brief Get the minimum allowable ratio between eigenvalues to prevent + * singular covariance matrices. \return the minimum allowable ratio between + * eigenvalues + */ + inline double getCovEigValueInflationRatio() { + return min_covar_eigvalue_mult_; + } + + /** \brief Filter cloud and initializes voxel structure. + * \param[out] output cloud containing centroids of voxels containing a + * sufficient number of points \param[in] searchable flag if voxel structure + * is searchable, if true then kdtree is built + */ + inline void filter(PointCloud& output, bool searchable = false) { + searchable_ = searchable; + applyFilter(output); + + voxel_centroids_ = PointCloudPtr(new PointCloud(output)); + + if (searchable_ && voxel_centroids_->size() > 0) { + // Initiates kdtree of the centroids of voxels containing a sufficient + // number of points + kdtree_.setInputCloud(voxel_centroids_); + } + } + + /** \brief Initializes voxel structure. + * \param[in] searchable flag if voxel structure is searchable, if true then + * kdtree is built + */ + inline void filter(bool searchable = false) { + searchable_ = searchable; + voxel_centroids_ = PointCloudPtr(new PointCloud); + applyFilter(*voxel_centroids_); + + if (searchable_ && voxel_centroids_->size() > 0) { + // Initiates kdtree of the centroids of voxels containing a sufficient + // number of points + kdtree_.setInputCloud(voxel_centroids_); + } + } + + /** \brief Get the voxel containing point p. + * \param[in] index the index of the leaf structure node + * \return const pointer to leaf structure + */ + inline LeafConstPtr getLeaf(int index) { + auto leaf_iter = leaves_.find(index); + if (leaf_iter != leaves_.end()) { + LeafConstPtr ret(&(leaf_iter->second)); + return ret; + } else + return NULL; + } + + /** \brief Get the voxel containing point p. + * \param[in] p the point to get the leaf structure at + * \return const pointer to leaf structure + */ + inline LeafConstPtr getLeaf(PointT& p) { + // Generate index associated with p + int ijk0 = static_cast(floor(p.x * inverse_leaf_size_[0]) - min_b_[0]); + int ijk1 = static_cast(floor(p.y * inverse_leaf_size_[1]) - min_b_[1]); + int ijk2 = static_cast(floor(p.z * inverse_leaf_size_[2]) - min_b_[2]); + + // Compute the centroid leaf index + int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; + + // Find leaf associated with index + auto leaf_iter = leaves_.find(idx); + if (leaf_iter != leaves_.end()) { + // If such a leaf exists return the pointer to the leaf structure + LeafConstPtr ret(&(leaf_iter->second)); + return ret; + } else + return NULL; + } + + /** \brief Get the voxel containing point p. + * \param[in] p the point to get the leaf structure at + * \return const pointer to leaf structure + */ + inline LeafConstPtr getLeaf(Eigen::Vector3f& p) { + // Generate index associated with p + int ijk0 = + static_cast(floor(p[0] * inverse_leaf_size_[0]) - min_b_[0]); + int ijk1 = + static_cast(floor(p[1] * inverse_leaf_size_[1]) - min_b_[1]); + int ijk2 = + static_cast(floor(p[2] * inverse_leaf_size_[2]) - min_b_[2]); + + // Compute the centroid leaf index + int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; + + // Find leaf associated with index + auto leaf_iter = leaves_.find(idx); + if (leaf_iter != leaves_.end()) { + // If such a leaf exists return the pointer to the leaf structure + LeafConstPtr ret(&(leaf_iter->second)); + return ret; + } else + return NULL; + } + + /** \brief Get the voxels surrounding point p, not including the voxel + * contating point p. \note Only voxels containing a sufficient number of + * points are used (slower than radius search in practice). \param[in] + * reference_point the point to get the leaf structure at \param[out] + * neighbors \return number of neighbors found + */ + int getNeighborhoodAtPoint(const Eigen::MatrixXi&, + const PointT& reference_point, + std::vector& neighbors) const; + int getNeighborhoodAtPoint(const PointT& reference_point, + std::vector& neighbors) const; + int getNeighborhoodAtPoint7(const PointT& reference_point, + std::vector& neighbors) const; + int getNeighborhoodAtPoint1(const PointT& reference_point, + std::vector& neighbors) const; + + /** \brief Get the leaf structure map + * \return a map contataining all leaves + */ + inline const Map& getLeaves() { + return leaves_; + } + + /** \brief Get a pointcloud containing the voxel centroids + * \note Only voxels containing a sufficient number of points are used. + * \return a map contataining all leaves + */ + inline PointCloudPtr getCentroids() { + return voxel_centroids_; + } + + /** \brief Get a cloud to visualize each voxels normal distribution. + * \param[out] cell_cloud a cloud created by sampling the normal distributions + * of each voxel + */ + void getDisplayCloud(pcl::PointCloud& cell_cloud); + + /** \brief Search for the k-nearest occupied voxels for the given query point. + * \note Only voxels containing a sufficient number of points are used. + * \param[in] point the given query point + * \param[in] k the number of neighbors to search for + * \param[out] k_leaves the resultant leaves of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the + * neighboring points \return number of neighbors found + */ + int nearestKSearch(const PointT& point, + int k, + std::vector& k_leaves, + std::vector& k_sqr_distances) { + k_leaves.clear(); + + // Check if kdtree has been built + if (!searchable_) { + PCL_WARN("%s: Not Searchable", this->getClassName().c_str()); + return 0; + } + + // Find k-nearest neighbors in the occupied voxel centroid cloud + std::vector k_indices; + k = kdtree_.nearestKSearch(point, k, k_indices, k_sqr_distances); + + // Find leaves corresponding to neighbors + k_leaves.reserve(k); + for (std::vector::iterator iter = k_indices.begin(); + iter != k_indices.end(); + iter++) { + k_leaves.push_back(&leaves_[voxel_centroids_leaf_indices_[*iter]]); + } + return k; + } + + /** \brief Search for the k-nearest occupied voxels for the given query point. + * \note Only voxels containing a sufficient number of points are used. + * \param[in] cloud the given query point + * \param[in] index the index + * \param[in] k the number of neighbors to search for + * \param[out] k_leaves the resultant leaves of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the + * neighboring points \return number of neighbors found + */ + inline int nearestKSearch(const PointCloud& cloud, + int index, + int k, + std::vector& k_leaves, + std::vector& k_sqr_distances) { + if (index >= static_cast(cloud.points.size()) || index < 0) + return (0); + return (nearestKSearch(cloud.points[index], k, k_leaves, k_sqr_distances)); + } + + /** \brief Search for all the nearest occupied voxels of the query point in a + * given radius. \note Only voxels containing a sufficient number of points + * are used. \param[in] point the given query point \param[in] radius the + * radius of the sphere bounding all of p_q's neighbors \param[out] k_leaves + * the resultant leaves of the neighboring points \param[out] k_sqr_distances + * the resultant squared distances to the neighboring points \param[in] max_nn + * \return number of neighbors found + */ + int radiusSearch(const PointT& point, + double radius, + std::vector& k_leaves, + std::vector& k_sqr_distances, + unsigned int max_nn = 0) const { + k_leaves.clear(); + + // Check if kdtree has been built + if (!searchable_) { + PCL_WARN("%s: Not Searchable", this->getClassName().c_str()); + return 0; + } + + // Find neighbors within radius in the occupied voxel centroid cloud + std::vector k_indices; + int k = + kdtree_.radiusSearch(point, radius, k_indices, k_sqr_distances, max_nn); + + // Find leaves corresponding to neighbors + k_leaves.reserve(k); + for (std::vector::iterator iter = k_indices.begin(); + iter != k_indices.end(); + iter++) { + auto leaf = leaves_.find(voxel_centroids_leaf_indices_[*iter]); + if (leaf == leaves_.end()) { + std::cerr + << "error : could not find the leaf corresponding to the voxel" + << std::endl; + std::cin.ignore(1); + } + k_leaves.push_back(&(leaf->second)); + } + return k; + } + + /** \brief Search for all the nearest occupied voxels of the query point in a + * given radius. \note Only voxels containing a sufficient number of points + * are used. \param[in] cloud the given query point \param[in] index a valid + * index in cloud representing a valid (i.e., finite) query point \param[in] + * radius the radius of the sphere bounding all of p_q's neighbors \param[out] + * k_leaves the resultant leaves of the neighboring points \param[out] + * k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn + * \return number of neighbors found + */ + inline int radiusSearch(const PointCloud& cloud, + int index, + double radius, + std::vector& k_leaves, + std::vector& k_sqr_distances, + unsigned int max_nn = 0) const { + if (index >= static_cast(cloud.points.size()) || index < 0) + return (0); + return (radiusSearch( + cloud.points[index], radius, k_leaves, k_sqr_distances, max_nn)); + } + +protected: + /** \brief Filter cloud and initializes voxel structure. + * \param[out] output cloud containing centroids of voxels containing a + * sufficient number of points + */ + void applyFilter(PointCloud& output); + + /** \brief Flag to determine if voxel structure is searchable. */ + bool searchable_; + + /** \brief Minimum points contained with in a voxel to allow it to be useable. + */ + int min_points_per_voxel_; + + /** \brief Minimum allowable ratio between eigenvalues to prevent singular + * covariance matrices. */ + double min_covar_eigvalue_mult_; + + /** \brief Voxel structure containing all leaf nodes (includes voxels with + * less than a sufficient number of points). */ + Map leaves_; + + /** \brief Point cloud containing centroids of voxels containing atleast + * minimum number of points. */ + PointCloudPtr voxel_centroids_; + + /** \brief Indices of leaf structurs associated with each point in \ref + * voxel_centroids_ (used for searching). */ + std::vector voxel_centroids_leaf_indices_; + + /** \brief KdTree generated using \ref voxel_centroids_ (used for searching). + */ + pcl::KdTreeFLANN kdtree_; +}; +} // namespace pclomp + +#endif //#ifndef PCL_VOXEL_GRID_COVARIANCE_H_ diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/voxel_grid_covariance_omp_impl.hpp b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/voxel_grid_covariance_omp_impl.hpp new file mode 100755 index 0000000..da1dee2 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/multithreaded_ndt/voxel_grid_covariance_omp_impl.hpp @@ -0,0 +1,487 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VOXEL_GRID_COVARIANCE_IMPL_OMP_H_ +#define PCL_VOXEL_GRID_COVARIANCE_IMPL_OMP_H_ + +#include +#include +#include "voxel_grid_covariance_omp.h" +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pclomp::VoxelGridCovariance::applyFilter (PointCloud &output) +{ + voxel_centroids_leaf_indices_.clear (); + + // Has the input dataset been set already? + if (!input_) + { + PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + // Copy the header (and thus the frame_id) + allocate enough space for points + output.height = 1; // downsampling breaks the organized structure + output.is_dense = true; // we filter out invalid points + output.points.clear (); + + Eigen::Vector4f min_p, max_p; + // Get the minimum and maximum dimensions + if (!filter_field_name_.empty ()) // If we don't want to process the entire cloud... + pcl::getMinMax3D (input_, filter_field_name_, static_cast (filter_limit_min_), static_cast (filter_limit_max_), min_p, max_p, filter_limit_negative_); + else + pcl::getMinMax3D (*input_, min_p, max_p); + + // Check that the leaf size is not too small, given the size of the data + int64_t dx = static_cast((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1; + int64_t dy = static_cast((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1; + int64_t dz = static_cast((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1; + + if((dx*dy*dz) > std::numeric_limits::max()) + { + PCL_WARN("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.", getClassName().c_str()); + output.clear(); + return; + } + + // Compute the minimum and maximum bounding box values + min_b_[0] = static_cast (floor (min_p[0] * inverse_leaf_size_[0])); + max_b_[0] = static_cast (floor (max_p[0] * inverse_leaf_size_[0])); + min_b_[1] = static_cast (floor (min_p[1] * inverse_leaf_size_[1])); + max_b_[1] = static_cast (floor (max_p[1] * inverse_leaf_size_[1])); + min_b_[2] = static_cast (floor (min_p[2] * inverse_leaf_size_[2])); + max_b_[2] = static_cast (floor (max_p[2] * inverse_leaf_size_[2])); + + // Compute the number of divisions needed along all axis + div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones (); + div_b_[3] = 0; + + // Clear the leaves + leaves_.clear (); +// leaves_.reserve(8192); + + // Set up the division multiplier + divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0); + + int centroid_size = 4; + + if (downsample_all_data_) + centroid_size = boost::mpl::size::value; + + // ---[ RGB special case + std::vector fields; + int rgba_index = -1; + rgba_index = pcl::getFieldIndex (*input_, "rgb", fields); + if (rgba_index == -1) + rgba_index = pcl::getFieldIndex (*input_, "rgba", fields); + if (rgba_index >= 0) + { + rgba_index = fields[rgba_index].offset; + centroid_size += 3; + } + + // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first... + if (!filter_field_name_.empty ()) + { + // Get the distance field index + std::vector fields; + int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields); + if (distance_idx == -1) + PCL_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n", getClassName ().c_str (), distance_idx); + + // First pass: go over all points and insert them into the right leaf + for (size_t cp = 0; cp < input_->points.size (); ++cp) + { + if (!input_->is_dense) + // Check if the point is invalid + if (!std::isfinite (input_->points[cp].x) || + !std::isfinite (input_->points[cp].y) || + !std::isfinite (input_->points[cp].z)) + continue; + + // Get the distance value + const uint8_t* pt_data = reinterpret_cast (&input_->points[cp]); + float distance_value = 0; + memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float)); + + if (filter_limit_negative_) + { + // Use a threshold for cutting out points which inside the interval + if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_)) + continue; + } + else + { + // Use a threshold for cutting out points which are too close/far away + if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_)) + continue; + } + + int ijk0 = static_cast (floor (input_->points[cp].x * inverse_leaf_size_[0]) - static_cast (min_b_[0])); + int ijk1 = static_cast (floor (input_->points[cp].y * inverse_leaf_size_[1]) - static_cast (min_b_[1])); + int ijk2 = static_cast (floor (input_->points[cp].z * inverse_leaf_size_[2]) - static_cast (min_b_[2])); + + // Compute the centroid leaf index + int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; + + Leaf& leaf = leaves_[idx]; + if (leaf.nr_points == 0) + { + leaf.centroid.resize (centroid_size); + leaf.centroid.setZero (); + } + + Eigen::Vector3d pt3d (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z); + // Accumulate point sum for centroid calculation + leaf.mean_ += pt3d; + // Accumulate x*xT for single pass covariance calculation + leaf.cov_ += pt3d * pt3d.transpose (); + + // Do we need to process all the fields? + if (!downsample_all_data_) + { + Eigen::Vector4f pt (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z, 0); + leaf.centroid.template head<4> () += pt; + } + else + { + // Copy all the fields + Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size); + // ---[ RGB special case + if (rgba_index >= 0) + { + // fill r/g/b data + int rgb; + memcpy (&rgb, reinterpret_cast (&input_->points[cp]) + rgba_index, sizeof (int)); + centroid[centroid_size - 3] = static_cast ((rgb >> 16) & 0x0000ff); + centroid[centroid_size - 2] = static_cast ((rgb >> 8) & 0x0000ff); + centroid[centroid_size - 1] = static_cast ((rgb) & 0x0000ff); + } + pcl::for_each_type (pcl::NdCopyPointEigenFunctor (input_->points[cp], centroid)); + leaf.centroid += centroid; + } + ++leaf.nr_points; + } + } + // No distance filtering, process all data + else + { + // First pass: go over all points and insert them into the right leaf + for (size_t cp = 0; cp < input_->points.size (); ++cp) + { + if (!input_->is_dense) + // Check if the point is invalid + if (!std::isfinite (input_->points[cp].x) || + !std::isfinite (input_->points[cp].y) || + !std::isfinite (input_->points[cp].z)) + continue; + + int ijk0 = static_cast (floor (input_->points[cp].x * inverse_leaf_size_[0]) - static_cast (min_b_[0])); + int ijk1 = static_cast (floor (input_->points[cp].y * inverse_leaf_size_[1]) - static_cast (min_b_[1])); + int ijk2 = static_cast (floor (input_->points[cp].z * inverse_leaf_size_[2]) - static_cast (min_b_[2])); + + // Compute the centroid leaf index + int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; + + //int idx = (((input_->points[cp].getArray4fmap () * inverse_leaf_size_).template cast ()).matrix () - min_b_).dot (divb_mul_); + Leaf& leaf = leaves_[idx]; + if (leaf.nr_points == 0) + { + leaf.centroid.resize (centroid_size); + leaf.centroid.setZero (); + } + + Eigen::Vector3d pt3d (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z); + // Accumulate point sum for centroid calculation + leaf.mean_ += pt3d; + // Accumulate x*xT for single pass covariance calculation + leaf.cov_ += pt3d * pt3d.transpose (); + + // Do we need to process all the fields? + if (!downsample_all_data_) + { + Eigen::Vector4f pt (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z, 0); + leaf.centroid.template head<4> () += pt; + } + else + { + // Copy all the fields + Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size); + // ---[ RGB special case + if (rgba_index >= 0) + { + // Fill r/g/b data, assuming that the order is BGRA + int rgb; + memcpy (&rgb, reinterpret_cast (&input_->points[cp]) + rgba_index, sizeof (int)); + centroid[centroid_size - 3] = static_cast ((rgb >> 16) & 0x0000ff); + centroid[centroid_size - 2] = static_cast ((rgb >> 8) & 0x0000ff); + centroid[centroid_size - 1] = static_cast ((rgb) & 0x0000ff); + } + pcl::for_each_type (pcl::NdCopyPointEigenFunctor (input_->points[cp], centroid)); + leaf.centroid += centroid; + } + ++leaf.nr_points; + } + } + + // Second pass: go over all leaves and compute centroids and covariance matrices + output.points.reserve (leaves_.size ()); + if (searchable_) + voxel_centroids_leaf_indices_.reserve (leaves_.size ()); + int cp = 0; + if (save_leaf_layout_) + leaf_layout_.resize (div_b_[0] * div_b_[1] * div_b_[2], -1); + + // Eigen values and vectors calculated to prevent near singluar matrices + Eigen::SelfAdjointEigenSolver eigensolver; + Eigen::Matrix3d eigen_val; + Eigen::Vector3d pt_sum; + + // Eigen values less than a threshold of max eigen value are inflated to a set fraction of the max eigen value. + double min_covar_eigvalue; + + for (auto it = leaves_.begin (); it != leaves_.end (); ++it) + { + + // Normalize the centroid + Leaf& leaf = it->second; + + // Normalize the centroid + leaf.centroid /= static_cast (leaf.nr_points); + // Point sum used for single pass covariance calculation + pt_sum = leaf.mean_; + // Normalize mean + leaf.mean_ /= leaf.nr_points; + + // If the voxel contains sufficient points, its covariance is calculated and is added to the voxel centroids and output clouds. + // Points with less than the minimum points will have a can not be accuratly approximated using a normal distribution. + if (leaf.nr_points >= min_points_per_voxel_) + { + if (save_leaf_layout_) + leaf_layout_[it->first] = cp++; + + output.push_back (PointT ()); + + // Do we need to process all the fields? + if (!downsample_all_data_) + { + output.points.back ().x = leaf.centroid[0]; + output.points.back ().y = leaf.centroid[1]; + output.points.back ().z = leaf.centroid[2]; + } + else + { + pcl::for_each_type (pcl::NdCopyEigenPointFunctor (leaf.centroid, output.back ())); + // ---[ RGB special case + if (rgba_index >= 0) + { + // pack r/g/b into rgb + float r = leaf.centroid[centroid_size - 3], g = leaf.centroid[centroid_size - 2], b = leaf.centroid[centroid_size - 1]; + int rgb = (static_cast (r)) << 16 | (static_cast (g)) << 8 | (static_cast (b)); + memcpy (reinterpret_cast (&output.points.back ()) + rgba_index, &rgb, sizeof (float)); + } + } + + // Stores the voxel indice for fast access searching + if (searchable_) + voxel_centroids_leaf_indices_.push_back (static_cast (it->first)); + + // Single pass covariance calculation + leaf.cov_ = (leaf.cov_ - 2 * (pt_sum * leaf.mean_.transpose ())) / leaf.nr_points + leaf.mean_ * leaf.mean_.transpose (); + leaf.cov_ *= (leaf.nr_points - 1.0) / leaf.nr_points; + + //Normalize Eigen Val such that max no more than 100x min. + eigensolver.compute (leaf.cov_); + eigen_val = eigensolver.eigenvalues ().asDiagonal (); + leaf.evecs_ = eigensolver.eigenvectors (); + + if (eigen_val (0, 0) < 0 || eigen_val (1, 1) < 0 || eigen_val (2, 2) <= 0) + { + leaf.nr_points = -1; + continue; + } + + // Avoids matrices near singularities (eq 6.11)[Magnusson 2009] + + min_covar_eigvalue = min_covar_eigvalue_mult_ * eigen_val (2, 2); + if (eigen_val (0, 0) < min_covar_eigvalue) + { + eigen_val (0, 0) = min_covar_eigvalue; + + if (eigen_val (1, 1) < min_covar_eigvalue) + { + eigen_val (1, 1) = min_covar_eigvalue; + } + + leaf.cov_ = leaf.evecs_ * eigen_val * leaf.evecs_.inverse (); + } + leaf.evals_ = eigen_val.diagonal (); + + leaf.icov_ = leaf.cov_.inverse (); + if (leaf.icov_.maxCoeff () == std::numeric_limits::infinity ( ) + || leaf.icov_.minCoeff () == -std::numeric_limits::infinity ( ) ) + { + leaf.nr_points = -1; + } + + } + } + + output.width = static_cast (output.points.size ()); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template int +pclomp::VoxelGridCovariance::getNeighborhoodAtPoint(const Eigen::MatrixXi& relative_coordinates, const PointT& reference_point, std::vector &neighbors) const +{ + neighbors.clear(); + + // Find displacement coordinates + Eigen::Vector4i ijk(static_cast (floor(reference_point.x / leaf_size_[0])), + static_cast (floor(reference_point.y / leaf_size_[1])), + static_cast (floor(reference_point.z / leaf_size_[2])), 0); + Eigen::Array4i diff2min = min_b_ - ijk; + Eigen::Array4i diff2max = max_b_ - ijk; + neighbors.reserve(relative_coordinates.cols()); + + // Check each neighbor to see if it is occupied and contains sufficient points + // Slower than radius search because needs to check 26 indices + for (int ni = 0; ni < relative_coordinates.cols(); ni++) + { + Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished(); + // Checking if the specified cell is in the grid + if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all()) + { + auto leaf_iter = leaves_.find(((ijk + displacement - min_b_).dot(divb_mul_))); + if (leaf_iter != leaves_.end() && leaf_iter->second.nr_points >= min_points_per_voxel_) + { + LeafConstPtr leaf = &(leaf_iter->second); + neighbors.push_back(leaf); + } + } + } + + return (static_cast (neighbors.size())); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template int +pclomp::VoxelGridCovariance::getNeighborhoodAtPoint(const PointT& reference_point, std::vector &neighbors) const +{ + neighbors.clear(); + + // Find displacement coordinates + Eigen::MatrixXi relative_coordinates = pcl::getAllNeighborCellIndices(); + return getNeighborhoodAtPoint(relative_coordinates, reference_point, neighbors); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template int +pclomp::VoxelGridCovariance::getNeighborhoodAtPoint7(const PointT& reference_point, std::vector &neighbors) const +{ + neighbors.clear(); + + Eigen::MatrixXi relative_coordinates(3, 7); + relative_coordinates.setZero(); + relative_coordinates(0, 1) = 1; + relative_coordinates(0, 2) = -1; + relative_coordinates(1, 3) = 1; + relative_coordinates(1, 4) = -1; + relative_coordinates(2, 5) = 1; + relative_coordinates(2, 6) = -1; + + return getNeighborhoodAtPoint(relative_coordinates, reference_point, neighbors); +} + + +////////////////////////////////////////////////////////////////////////////////////////// +template int +pclomp::VoxelGridCovariance::getNeighborhoodAtPoint1(const PointT& reference_point, std::vector &neighbors) const +{ + neighbors.clear(); + return getNeighborhoodAtPoint(Eigen::MatrixXi::Zero(3,1), reference_point, neighbors); +} + + + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pclomp::VoxelGridCovariance::getDisplayCloud (pcl::PointCloud& cell_cloud) +{ + cell_cloud.clear (); + + int pnt_per_cell = 1000; + boost::mt19937 rng; + boost::normal_distribution<> nd (0.0, leaf_size_.head (3).norm ()); + boost::variate_generator > var_nor (rng, nd); + + Eigen::LLT llt_of_cov; + Eigen::Matrix3d cholesky_decomp; + Eigen::Vector3d cell_mean; + Eigen::Vector3d rand_point; + Eigen::Vector3d dist_point; + + // Generate points for each occupied voxel with sufficient points. + for (auto it = leaves_.begin (); it != leaves_.end (); ++it) + { + Leaf& leaf = it->second; + + if (leaf.nr_points >= min_points_per_voxel_) + { + cell_mean = leaf.mean_; + llt_of_cov.compute (leaf.cov_); + cholesky_decomp = llt_of_cov.matrixL (); + + // Random points generated by sampling the normal distribution given by voxel mean and covariance matrix + for (int i = 0; i < pnt_per_cell; i++) + { + rand_point = Eigen::Vector3d (var_nor (), var_nor (), var_nor ()); + dist_point = cell_mean + cholesky_decomp * rand_point; + cell_cloud.push_back (pcl::PointXYZ (static_cast (dist_point (0)), static_cast (dist_point (1)), static_cast (dist_point (2)))); + } + } + } +} + +#define PCL_INSTANTIATE_VoxelGridCovariance(T) template class PCL_EXPORTS pcl::VoxelGridCovariance; + +#endif // PCL_VOXEL_GRID_COVARIANCE_IMPL_H_ diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_localization/PointCloudLocalization.h b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_localization/PointCloudLocalization.h new file mode 100755 index 0000000..dc40cae --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_localization/PointCloudLocalization.h @@ -0,0 +1,181 @@ +/* + * Copyright (c) 2016, The Regents of the University of California (Regents). + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are + * met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS AS IS + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Please contact the author(s) of this library if you have any questions. + * Authors: Erik Nelson ( eanelson@eecs.berkeley.edu ) + */ + +#ifndef POINT_CLOUD_LOCALIZATION_H +#define POINT_CLOUD_LOCALIZATION_H + +//#include + +#include +#include + + +#include +#include + +#include +#include +#include + +#include +#include + +#include +#include +#include + +using pcl::transformPointCloud; + +namespace point_cloud_localization{ + +//enum RegistrationMethod { GICP, NDT }; + + +class PointCloudLocalization { +public: + typedef pcl::PointCloud PointNormal; + typedef pcl::search::KdTree KdTree; + + PointCloudLocalization(); + ~PointCloudLocalization(); + + bool Initialize(std::string path_to_params); + + // Transform a point cloud from the sensor frame into the fixed frame using + // the current best position estimate + bool TransformPointsToFixedFrame(const PointCloudF &points, + PointCloudF *points_transformed) const; + + // Transform a point cloud from the fixed frame into the sensor frame using + // the current best position estimate + bool TransformPointsToSensorFrame(const PointCloudF &points, + PointCloudF *points_transformed) const; + + // Store incremental estimate from odometry + bool MotionUpdate(const geometry_utils::Transform3 &incremental_odom); + + // Align incoming point cloud with a reference point cloud from the map. + // Output the query scan aligned in the localization frame + bool MeasurementUpdate(const PointCloudF::Ptr &query, + const PointCloudF::Ptr &reference, PointCloudF *aligned_query); + + bool MeasurementUpdateRelocalization(const PointCloudF::Ptr &query, + const PointCloudF::Ptr &reference, PointCloudF *aligned_query); + + // Get pose estimates. + const geometry_utils::Transform3& GetIncrementalEstimate() const; + const geometry_utils::Transform3& GetIntegratedEstimate() const; + + // Set integrated estimate. Useful for graph SLAM whenever the pose graph is + // updated and the map is regenerated + void + SetIntegratedEstimate( + const geometry_utils::Transform3 &integrated_estimate); + + // Pose estimate + // TODO: why do we need an interface if we have them as a public? + geometry_utils::Transform3 incremental_estimate_; + geometry_utils::Transform3 integrated_estimate_; + + // ICP fitness score + double icpFitnessScore_; + + // Aligned point cloud returned by ICP + PointCloudF icpAlignedPointsLocalization_; + + void SetFlatGroundAssumptionValue(const bool &value); + + inline double getFitnessScore() { + return score_registration_; + } + +private: + bool loadParametersFromFile(std::string path_to_file); + void applyParameters(); + + // when scan is processed; + double timestamp_; // nano-sec; + + // Parameters for filtering and ICP + struct Parameters { + // What registration method should be used: GICP, NDT + std::string registration_method; + // Compute ICP covariance and condition number + bool compute_icp_covariance; + // Point-to-point or Point-to-plane + int icp_covariance_method; + // Max boundd for icp covariance + double icp_max_covariance; + // Compute ICP observability + bool compute_icp_observability; + // Stop ICP if the transformation from the last iteration was this small + double tf_epsilon; + // During ICP, two points won't be considered a correspondence if they are + // at least this far from one another + double corr_dist; + // Iterate ICP this many times + unsigned int iterations; + // Number of threads GICP is allowed to use + int num_threads; + // Enable GICP timing information print logs + bool enable_timing_output; + // Radius used when computing ptcld normals + // double normal_radius_; + int k_nearest_neighbours_; + } params_; + + // ICP + pcl::Registration::Ptr icp_; + double score_registration_ { 0.0 }; + bool recompute_covariance_local_map_; + bool recompute_covariance_scan_; + + // Maximum acceptable translation and rotation tolerances. + // If transform_thresholding_ is set to false, + // neither of these thresholds are considered + bool transform_thresholding_; + double max_translation_; + double max_rotation_; + bool b_is_flat_ground_assumption_; + + bool SetupICP(); + + std::string log_tag{"component-localizer"}; +}; + +} + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_localization/utils.h b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_localization/utils.h new file mode 100755 index 0000000..2161b9a --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_localization/utils.h @@ -0,0 +1,40 @@ +/* +point_cloud_localization/utils.h +author: Yun Chang yunchang@mit.edu + +Utilitiy functions for point cloud localization and ICP +*/ + +#ifndef UTILS_H +#define UTILS_H + +#include +#include +#include +#include +#include +#include + +void addNormal(const PointCloudF& cloud, + pcl::PointCloud::Ptr& cloud_with_normals, + const int k_nearest_neighbours); + +void addNormal(const PointCloudF& cloud, + PointCloudF::Ptr& cloud_with_normals, + const int k_nearest_neighbours); + +// returns a point cloud whose centroid is the origin, and that the mean of the +// distances to the origin is 1 +void normalizePCloud(const pcl::PointCloud& cloud, + pcl::PointCloud::Ptr pclptr_normalized); +void normalizePCloud(const PointCloudF& cloud, + PointCloudF::Ptr pclptr_normalized); + +void doEigenDecomp6x6(const Eigen::Matrix& data, + Eigen::Matrix& eigenvalues, + Eigen::Matrix& eigenvectors); + +void doEigenDecomp3x3(const Eigen::Matrix& data, + Eigen::Matrix& eigenvalues, + Eigen::Matrix& eigenvectors); +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/IPointCloudMapper.h b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/IPointCloudMapper.h new file mode 100755 index 0000000..74b1f3d --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/IPointCloudMapper.h @@ -0,0 +1,57 @@ +#pragma once + +#include +#include + +#include + +#include +#include + + +class IPointCloudMapper { +public: + using Ptr = std::shared_ptr; + IPointCloudMapper() { + } + ; + virtual ~IPointCloudMapper() { + } + ; + + virtual bool Initialize(std::string path_to_params) = 0; + + // Resets the octree and stored points to an empty map. This is used when + // closing loops or otherwise regenerating the map from scratch. + virtual void Reset() = 0; + + // Adds a set of points to the datastructure + virtual bool InsertPoints(const PointCloudF::ConstPtr &points, + PointCloudF *incremental_points) = 0; + + virtual bool ApproxNearestNeighbors(const PointCloudF &points, + PointCloudF *neighbors) = 0; + // Setting size of the local window map. + virtual void SetBoxFilterSize(const int box_filter_size) = 0; + + void SetupNumberThreads(int no_threads) { + number_threads_ = no_threads; + LOG(INFO) << "Setting up number threads for local mapping: " << number_threads_; + } + +// virtual void Refresh(const geometry_utils::Transform3 ¤t_pose) = 0; + + void UpdateCurrentPose(const geometry_utils::Transform3 ¤t_pose) { + current_pose_estimate_ = current_pose; + } + + +private: + virtual bool loadParametersFromFile(std::string path_to_file) = 0; + +protected: + + PointCloudF::Ptr map_data_; + geometry_utils::Transform3 current_pose_estimate_; + int number_threads_ { 1 }; +}; diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/PointCloudIkdTreeMapper.h b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/PointCloudIkdTreeMapper.h new file mode 100755 index 0000000..af6567c --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/PointCloudIkdTreeMapper.h @@ -0,0 +1,64 @@ +#pragma once + +#include + +#include +#include + +#include +#include + +#include "IPointCloudMapper.h" +#include "ikd_tree/ikd_Tree.h" + +//#include +//#include + +#include + +#include + +class PointCloudIkdTreeMapper: public IPointCloudMapper { +public: + // typedef pcl::PointCloud PointCloud; + + PointCloudIkdTreeMapper(); + ~PointCloudIkdTreeMapper(); + + bool Initialize(std::string path_to_params) override; + // Resets the octree and stored points to an empty map. This is used when + // closing loops or otherwise regenerating the map from scratch. + void Reset(); + + // Adds a set of points to the octree. Only inserts points if one does not + // already exist in the corresponding voxel. Output the points from the input + // that ended up being inserted into the octree. + // Effective C++ item 37 + bool InsertPoints(const PointCloudF::ConstPtr &points, + PointCloudF *incremental_points) override; + + // Returns the approximate nearest neighbor for every point in the input point + // cloud. Localization to the map can be performed by doing ICP between the + // input and output. Returns true if at least one of the inputs points had a + // nearest neighbor. + virtual bool ApproxNearestNeighbors(const PointCloudF &points, + PointCloudF *neighbors) override; + + + PointCloudF::Ptr getCloudMapInMem(); + + // to drop; + void SetBoxFilterSize(const int box_filter_size) override; +private: + + bool loadParametersFromFile(std::string path_to_file) override; + + std::string fixed_frame_id_; + double octree_resolution_; + bool initialized_; + + int num_threads_{2}; + + mutable std::mutex map_mutex_; + KD_TREE ikdtree; +}; diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/settings.h b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/settings.h new file mode 100755 index 0000000..806220d --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_mapper/settings.h @@ -0,0 +1,70 @@ +#pragma once + +#include +#include +#include + +enum class MappingMethod { + MAPPER, + BUFFER_MAPPER, + OCTOMAP_MAPPER, + VDB_MAPPER, + KFLANN, + MULTI_THREADED_MAPPER, + IKDTREE_MAPPER +}; + +using EnumToStringMappingMethods = std::pair; + +const std::vector EnumToStringMappingMethodsVector = + {EnumToStringMappingMethods("mapper", MappingMethod::MAPPER), + EnumToStringMappingMethods("buffer_mapper", MappingMethod::BUFFER_MAPPER), + EnumToStringMappingMethods("kflann", MappingMethod::KFLANN), + EnumToStringMappingMethods("octomap_mapper", + MappingMethod::OCTOMAP_MAPPER), + EnumToStringMappingMethods("vdb_mapper", MappingMethod::VDB_MAPPER), + EnumToStringMappingMethods("multi_threaded_mapper", + MappingMethod::MULTI_THREADED_MAPPER), + EnumToStringMappingMethods("ikdtree_mapper", + MappingMethod::IKDTREE_MAPPER)}; +// TODO: maybe somehow varialbe template, but it's available from cpp17 i think +MappingMethod getCalibrationMethodFromString(const std::string& mode) { + for (const auto& available_vlo : EnumToStringMappingMethodsVector) { + if (mode == available_vlo.first) { + return available_vlo.second; + } + } + throw std::runtime_error("No such mapping mode!: " + mode); +} + +IPointCloudMapper::Ptr mapperFabric(const std::string& mapping_method) { + switch (getCalibrationMethodFromString(mapping_method)) { + case MappingMethod::MAPPER: { + ROS_INFO_STREAM("MappingMethod::MAPPER activated."); + return std::make_shared(); + } + case MappingMethod::MULTI_THREADED_MAPPER: { + ROS_INFO_STREAM("MappingMethod::MULTI_THREADED_MAPPER activated."); + return std::make_shared(); + } + case MappingMethod::IKDTREE_MAPPER: { + ROS_INFO_STREAM("MappingMethod::IKDTREE_MAPPER activated."); + return std::make_shared(); + } + // case MappingMethod::OCTOMAP_MAPPER: { + // ROS_INFO_STREAM("MappingMethod::OCTOMAP_MAPPER activated."); + // return std::make_shared(); + // } + // case MappingMethod::VDB_MAPPER: { + // ROS_INFO_STREAM("MappingMethod::VDB_MAPPER activated."); + // return std::make_shared(); + // } + // case MappingMethod::KFLANN: { + // ROS_INFO_STREAM("MappingMethod::KFLANN acticated."); + // return std::make_shared(); + // } + default: + throw std::runtime_error("No such mapping mode or not implemented yet " + + mapping_method); + } +} diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_odometry/PointCloudOdometry.h b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_odometry/PointCloudOdometry.h new file mode 100755 index 0000000..4f2da08 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/point_cloud_odometry/PointCloudOdometry.h @@ -0,0 +1,141 @@ +/* + * Copyright (c) 2016, The Regents of the University of California (Regents). + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are + * met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS AS IS + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Please contact the author(s) of this library if you have any questions. + * Authors: Erik Nelson ( eanelson@eecs.berkeley.edu ) + */ + +#ifndef POINT_CLOUD_ODOMETRY_H +#include +#include +#include + +#include +#include + +#include + + +namespace point_cloud_odometry{ +enum RegistrationMethod { GICP, NDT }; + + +class PointCloudOdometry { +public: + PointCloudOdometry(); + ~PointCloudOdometry(); + + inline void reset() { + initialized_ = false; + } + + bool Initialize(std::string path_to_file); + + bool SetLidar(const PointCloudF &points); + bool SetImuDelta(const Eigen::Matrix3d &imu_delta); + bool UpdateEstimate(); + + const geometry_utils::Transform3& GetIncrementalEstimate() const; + const geometry_utils::Transform3& GetIntegratedEstimate() const; + + bool GetLastPointCloud(PointCloudF::Ptr &out) const; + + // Aligned point cloud returned by ICP + PointCloudF icpAlignedPointsOdometry_; + + void EnableImuIntegration(); + void EnableOdometryIntegration(); + void DisableSensorIntegration(); + + void SetFlatGroundAssumptionValue(const bool &value); + +private: + + geometry_utils::Transform3 incremental_estimate_; + geometry_utils::Transform3 integrated_estimate_; + + bool loadParametersFromFile(std::string path_to_file); + void applyParameters(); + + // Use ICP between a query and reference point cloud to estimate pose + bool UpdateICP(); + + std::string name_; + bool b_verbose_; + bool initialized_; + + // Coordinate frames + bool b_is_flat_ground_assumption_; + bool recompute_covariances_; + + // Point cloud containers + PointCloudF points_; + PointCloudF::Ptr query_; + PointCloudF::Ptr reference_; + PointCloudF::Ptr query_trans_; + + // Maximum acceptable translation and rotation tolerances + // If transform_thresholding_ is set to false, + // neither of these thresholds are considered + bool transform_thresholding_; + double max_translation_; + double max_rotation_; + + // ICP + struct Parameters { + // Registration method + std::string registration_method; + double icp_tf_epsilon; + double icp_corr_dist; + unsigned int icp_iterations; + // Number of threads GICP is allowed to use + int num_threads; + // Enable GICP timing information print logs + bool enable_timing_output; + + } params_; + + pcl::Registration::Ptr icp_; + + bool SetupICP(); + + // prior storage for relative displacement; + bool b_use_imu_integration_; + Eigen::Matrix3d imu_delta_; + Eigen::Matrix4d imu_prior_; + + std::string log_tag{"component-icp"}; +}; + +} + +#endif diff --git a/src/localization_module_lio_locus/include/lio_locus_humble/registration_settings.h b/src/localization_module_lio_locus/include/lio_locus_humble/registration_settings.h new file mode 100755 index 0000000..fba3152 --- /dev/null +++ b/src/localization_module_lio_locus/include/lio_locus_humble/registration_settings.h @@ -0,0 +1,20 @@ +#pragma once + +enum class RegistrationMethod { GICP, NDT }; + +using EnumToStringRegistrationMethods = + std::pair; + +const std::vector + EnumToStringRegistrationMethodsVector = { + EnumToStringRegistrationMethods("gicp", RegistrationMethod::GICP), + EnumToStringRegistrationMethods("ndt", RegistrationMethod::NDT)}; +// TODO: maybe somehow varialbe template, but it's available from cpp17 i think +RegistrationMethod getRegistrationMethodFromString(const std::string& mode) { + for (const auto& available_vlo : EnumToStringRegistrationMethodsVector) { + if (mode == available_vlo.first) { + return available_vlo.second; + } + } + throw std::runtime_error("No such Registration mode!: " + mode); +} diff --git a/src/localization_module_lio_locus/launch/__pycache__/cloud_conversion.launch.cpython-38.pyc b/src/localization_module_lio_locus/launch/__pycache__/cloud_conversion.launch.cpython-38.pyc new file mode 100755 index 0000000000000000000000000000000000000000..98b32f71c076e71abd6374f0874e4e4da6bafd91 GIT binary patch literal 978 zcmZ8g&2H2%5RRRn&1SRPZP_9O7p}P!wc>~ns4Wr*RV!6odM45tCR9$xtLD>9~-OL`u@mj`&zi$OP;GjlXzg ziw;k{Ecpqicp0+W?+a6x%Oj>rS+%-q>I~c6BUbW4vVQHgTo}P>Z70W9tTdXt$0PU$qiaxnq$H zP8!PKfBL4X>AWZ}iUm7eLLH?m_I@BRMlcUysv`gmVy)0;Pa};fraldBFjygtI?JcX zU7ZefK=BFzhATvquXusz=q6nFD+Ge1CuGX2Cg)9QRK7Igj5CX?`qSWyk?r*g2-Y{1lA+^gYhG=% zkm_zG2e2+<7qrs{xfj^GPwf;Sk2V(m&Cu!PYV7pbfL-8h{6aL;aQ4!*oJs*wG({7Ctsp?sg81Tef&E2_~!j&5_`~ou&34Y!1KPl&UVAlc?qxj06;y8xF--n z$i9B`i&nx`?pS1llZG<* z&R$nFUFOAkUb53Q=qQ}n+lC-;RvyBu4gfTmb%nlo8fi?i_CI^nr$OmoAsSv|9Z*Cg zmpmQmkm4&;p%T&fIxHauE5;{e#;YddO<`2FHsXvk8@0L2g|bo6=q>e literal 0 HcmV?d00001 diff --git a/src/localization_module_lio_locus/launch/nodelets/__pycache__/imu_preprocessing_livox.launch.cpython-38.pyc b/src/localization_module_lio_locus/launch/nodelets/__pycache__/imu_preprocessing_livox.launch.cpython-38.pyc new file mode 100755 index 0000000000000000000000000000000000000000..404a1f01cc6e518f50579cc1baf434cc43eff31d GIT binary patch literal 972 zcmZWoU2oGc6pfvawrN^A=q3;n5|4T5FF@1KHl!gmRhoG5OUPn3jbC;kE;jq9Y_ig1tp-++>@J+lS%BsU?;oPJn+09Zn8ZvOb*~tp8%*w5%&Zl z2)P(@EPUdNfCSy#=b?y5)WrcGh#?t@5gCb?#2pv%u}DbL#Sx!~DVah%pu=w-c|u2L zUK;;|Tf7w6oe#OGi}evxg{)d#HFb*Z?hz|^E?K|!R+dJvTHERI6)TKpOW71mDL6eo zSsgYtt-5o*ebyfUYE_j+=8m@WWv`QJ=;ll_sj`R7 zi|br)&^w`Ql^d?J%bXiV_9|gAD68#ls_HVUp)fLfIA|kqo3WaVR~2Vje^(mXLE9H? zW7avHJ1Ie(3lP*8-5PDoe$D=j`ST29E==904XBl!bl0PE^9B!@1C3k`|I`p z@_2RGTrGIl35)jHzARbI;PtVr=Q8@(9uvr+UIBP$h_FA$7;Sz&_M$s{hkplu@SWU) z9jEEcMtzD-C7EvS$P3p5s#gtPgGY8YE8utEPD+N3pKo}z)jX;zudjCKHa+b(WwKF= t`_#?`@_cLI-wd5|PGe`v7VH9Nhi^nf4QKnV*;E3MpczWgJWNpH{{{2&5;y<= literal 0 HcmV?d00001 diff --git a/src/localization_module_lio_locus/launch/nodelets/__pycache__/lio_locus.launch.cpython-38.pyc b/src/localization_module_lio_locus/launch/nodelets/__pycache__/lio_locus.launch.cpython-38.pyc new file mode 100755 index 0000000000000000000000000000000000000000..5d97830ef43c38342c55cc4a64fdfc2b840eb97a GIT binary patch literal 957 zcmY*X-EPw`6t?E=sv>~`a<8}|i zEBTfyUICECang0gkx!04A0L0`^Z78DLl%l)6*-Sw}!7&opY_>^!V-i zxUN{)o%8Hbe*mC$S+pv1u$`|mvw2sS)p>iNO=;Q=ovp6Trmjw}8U?A`wb=S+HRJG~ zy(ufU%JR#s;O86Qkvp>Y1B2tFJcg-Xf-xZ04gQJ@HiQx5eL>7)e&O9<7Tgl!Gt5F) zJR6ySksDm%0<-8gD8L6P#%FXU$~qNw-s*JI$_v45*kme`+J<>o%jc)vnj5Zkx(i-j zXHo#)3FGUm6(;?ZiI&sFE?}E2t)MPC+QBviu{p2kcwGvf_E#l=9W;H-HsYPonPcKt znFKy{Yns;B=z&KPDkp<-jiWqg2F{F}3Be?oj`LP2c)7H>EPfz02lV&Rj>b}SPrq!g z?X!Yc9NvqkJ(jYEewe^1{TvL!LrlCmA$a?F1ci6xj{Ncek~{SnBF>VT4f_-wFFM`c zk>&2ybgyZ2pu;{WRkdE;r*?(YCwm+JXXvzY h96K5I%mOewd?9Pr3jWe{myW^2c!py<4`Lj9{{XRe3*!I) literal 0 HcmV?d00001 diff --git a/src/localization_module_lio_locus/launch/nodelets/cloud_preprocessing.launch.py b/src/localization_module_lio_locus/launch/nodelets/cloud_preprocessing.launch.py new file mode 100755 index 0000000..dbf1d2f --- /dev/null +++ b/src/localization_module_lio_locus/launch/nodelets/cloud_preprocessing.launch.py @@ -0,0 +1,34 @@ +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, ExecuteProcess +from launch.conditions import IfCondition +from launch.substitutions import ( + LaunchConfiguration, + PathJoinSubstitution, + PythonExpression, +) +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + current_pkg = FindPackageShare("lio_locus_humble") + return LaunchDescription( + [ + # ROS 2 parameters + DeclareLaunchArgument("params", default_value=PathJoinSubstitution([current_pkg, "config", "parameters_lio_locus.yaml"])), + # ROS2 Nodes + Node( + package="lio_locus_humble", + executable="cloud_preprocessing_node", + name="cloud_preprocessing", + output="screen", + parameters=[ + { + "file_params": LaunchConfiguration("params"), + } + ], + ), + ] + ) + + diff --git a/src/localization_module_lio_locus/launch/nodelets/imu_preprocessing_livox.launch.py b/src/localization_module_lio_locus/launch/nodelets/imu_preprocessing_livox.launch.py new file mode 100755 index 0000000..dd24a5e --- /dev/null +++ b/src/localization_module_lio_locus/launch/nodelets/imu_preprocessing_livox.launch.py @@ -0,0 +1,36 @@ +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, ExecuteProcess +from launch.conditions import IfCondition +from launch.substitutions import ( + LaunchConfiguration, + PathJoinSubstitution, + PythonExpression, +) +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + current_pkg = FindPackageShare("lio_locus_humble") + return LaunchDescription( + [ + # ROS 2 parameters + DeclareLaunchArgument("params", default_value=PathJoinSubstitution([current_pkg, "config", "parameters_lio_locus.yaml"])), + # ROS2 Nodes + Node( + package="lio_locus_humble", + executable="imu_preprocessing_node", + name="lio_locus", + output="screen", + parameters=[ + { + "file_params": LaunchConfiguration("params"), + } + ], + ), + ] + ) + + + + diff --git a/src/localization_module_lio_locus/launch/nodelets/lio_locus.launch.py b/src/localization_module_lio_locus/launch/nodelets/lio_locus.launch.py new file mode 100755 index 0000000..eab222b --- /dev/null +++ b/src/localization_module_lio_locus/launch/nodelets/lio_locus.launch.py @@ -0,0 +1,36 @@ +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, ExecuteProcess +from launch.conditions import IfCondition +from launch.substitutions import ( + LaunchConfiguration, + PathJoinSubstitution, + PythonExpression, +) +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + current_pkg = FindPackageShare("lio_locus_humble") + return LaunchDescription( + [ + # ROS 2 parameters + DeclareLaunchArgument("params", default_value=PathJoinSubstitution([current_pkg, "config", "parameters_lio_locus.yaml"])), + # ROS2 Nodes + Node( + package="lio_locus_humble", + executable="lio_locus_node", + prefix="gdb -ex run --args", + name="lio_locus", + output="screen", + parameters=[ + { + "file_params": LaunchConfiguration("params"), + } + ], + ), + ] + ) + + + diff --git a/src/localization_module_lio_locus/launch/nodelets/vis_ego_viewpoint.launch.py b/src/localization_module_lio_locus/launch/nodelets/vis_ego_viewpoint.launch.py new file mode 100755 index 0000000..545373c --- /dev/null +++ b/src/localization_module_lio_locus/launch/nodelets/vis_ego_viewpoint.launch.py @@ -0,0 +1,22 @@ +from launch import LaunchDescription +from launch.substitutions import ( + PathJoinSubstitution, +) +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + current_pkg = FindPackageShare("lio_locus_humble") + return LaunchDescription( + [ + Node( + package="rviz2", + executable="rviz2", + output={"both": "log"}, + arguments=["-d", PathJoinSubstitution([current_pkg, "rviz", "ego_view_titan.rviz"])], + ), + ] + ) + + diff --git a/src/localization_module_lio_locus/launch/nodelets/vis_world_viewpoint.launch.py b/src/localization_module_lio_locus/launch/nodelets/vis_world_viewpoint.launch.py new file mode 100755 index 0000000..e8e6aba --- /dev/null +++ b/src/localization_module_lio_locus/launch/nodelets/vis_world_viewpoint.launch.py @@ -0,0 +1,21 @@ +from launch import LaunchDescription +from launch.substitutions import ( + PathJoinSubstitution, +) +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + current_pkg = FindPackageShare("lio_locus_humble") + return LaunchDescription( + [ + Node( + package="rviz2", + executable="rviz2", + output={"both": "log"}, + arguments=["-d", PathJoinSubstitution([current_pkg, "rviz", "world_view_titan.rviz"])], + ), + ] + ) + diff --git a/src/localization_module_lio_locus/package.xml b/src/localization_module_lio_locus/package.xml new file mode 100755 index 0000000..9d4e9e8 --- /dev/null +++ b/src/localization_module_lio_locus/package.xml @@ -0,0 +1,26 @@ + + + + lio_locus_humble + 1.0.0 + loosely-coupled-lidar-inertial-odometry + root + MIT + + ament_cmake + + rclcpp + std_msgs + sensor_msgs + nav_msgs + pcl_conversions + tf2 + tf2_ros + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/src/localization_module_lio_locus/rviz/ego_view_titan.rviz b/src/localization_module_lio_locus/rviz/ego_view_titan.rviz new file mode 100755 index 0000000..63c3e69 --- /dev/null +++ b/src/localization_module_lio_locus/rviz/ego_view_titan.rviz @@ -0,0 +1,323 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /Grid1 + - /LioLocus1/Odometry1/Shape1 + - /LioLocus1/cloud_map1 + - /CloudRaw1 + - /CloudRaw1/cloud_input1 + - /Axes1 + Splitter Ratio: 0.5 + Tree Height: 1079 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: cloud_input +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 5 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 60 + Reference Frame: + Value: true + - Class: rviz_common/Group + Displays: + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 1 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 6 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 6 + Shaft Radius: 0.10000000149011612 + Value: Axes + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /pose_lo + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 255 + Min Color: 0; 0; 0 + Min Intensity: 1 + Name: cloud_map + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.11999999731779099 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_map + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 223 + Min Color: 0; 0; 0 + Min Intensity: 1 + Name: localized_cloud + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.20000000298023224 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /dbg_localized_cloud + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz_default_plugins/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /dbg_lio_path + Value: true + Enabled: true + Name: LioLocus + - Class: rviz_common/Group + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 123.83333587646484 + Min Color: 0; 0; 0 + Min Intensity: 0.19392558932304382 + Name: cloud_input + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_input + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Name: CloudRaw + - Class: rviz_default_plugins/Axes + Enabled: true + Length: 6 + Name: Axes + Radius: 0.10000000149011612 + Reference Frame: base_link + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/XYOrbit + Distance: 38.536495208740234 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -2.5817513465881348 + Y: -5.34882926940918 + Z: 1.5393958165077493e-05 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.6497955918312073 + Target Frame: + Value: XYOrbit (rviz_default_plugins) + Yaw: 2.5491929054260254 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1376 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd000000040000000000000156000004c2fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000004c2000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000305fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000305000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004dc0000003efc0100000002fb0000000800540069006d00650100000000000004dc000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000380000004c200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1244 + X: 1316 + Y: 27 diff --git a/src/localization_module_lio_locus/rviz/world_view_titan.rviz b/src/localization_module_lio_locus/rviz/world_view_titan.rviz new file mode 100755 index 0000000..22c7c52 --- /dev/null +++ b/src/localization_module_lio_locus/rviz/world_view_titan.rviz @@ -0,0 +1,412 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /Grid1 + - /TF1/Frames1 + - /LioLocus1 + - /LioLocus1/Odometry1/Shape1 + - /LioLocus1/cloud_map1 + - /LioLocus1/OdometryLidar1/Shape1 + - /Axes1 + - /CloudRaw1 + Splitter Ratio: 0.5 + Tree Height: 719 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: localized_cloud +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 300 + Reference Frame: + Value: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + Marker Scale: 6 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + {} + Update Interval: 0 + Value: true + - Class: rviz_common/Group + Displays: + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 1 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 6 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 6 + Shaft Radius: 0.10000000149011612 + Value: Axes + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /pose_lo + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 255 + Min Color: 0; 0; 0 + Min Intensity: 1 + Name: cloud_map + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.12999999523162842 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_map + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 144.3333282470703 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: localized_cloud + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /dbg_localized_cloud + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz_default_plugins/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /dbg_lio_path + Value: true + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 1 + Name: OdometryLidar + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 6 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Axes + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /pose_lidar + Value: true + Enabled: true + Name: LioLocus + - Class: rviz_default_plugins/Axes + Enabled: false + Length: 6 + Name: Axes + Radius: 0.10000000149011612 + Reference Frame: fixed + Value: false + - Class: rviz_common/Group + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 255 + Min Color: 0; 0; 0 + Min Intensity: 1 + Name: cloud_raw + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.05999999865889549 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /rsm1_1 + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 209 + Min Color: 0; 0; 0 + Min Intensity: 1 + Name: cloud_input + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.30000001192092896 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cloud_input + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Name: CloudRaw + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: fixed + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/XYOrbit + Distance: 28.173295974731445 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.9926908612251282 + Y: 1.7843061685562134 + Z: -5.0866601668531075e-05 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.43979689478874207 + Target Frame: + Value: XYOrbit (rviz_default_plugins) + Yaw: 4.894167423248291 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1016 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd0000000400000000000001560000035afc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000035a000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000305fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000305000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000003efc0100000002fb0000000800540069006d0065010000000000000738000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005dc0000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1848 + X: 463 + Y: 143 diff --git a/src/localization_module_lio_locus/src/CMakeLists.txt b/src/localization_module_lio_locus/src/CMakeLists.txt new file mode 100755 index 0000000..c08f13e --- /dev/null +++ b/src/localization_module_lio_locus/src/CMakeLists.txt @@ -0,0 +1,5 @@ +add_subdirectory(point_cloud_odometry) +add_subdirectory(point_cloud_localization) +add_subdirectory(point_cloud_mapper) +#add_subdirectory(lio_locus) + diff --git a/src/localization_module_lio_locus/src/lio_locus/.lio_locus.cpp.swp b/src/localization_module_lio_locus/src/lio_locus/.lio_locus.cpp.swp new file mode 100755 index 0000000000000000000000000000000000000000..f73ebfca334f2cb6c30692ab397b6ca7d8c27549 GIT binary patch literal 16384 zcmeHNO>87b6>cCT43I2@z#&qgY#$h}+ JL{aaqVR5p~Abah#y)2t3wA#}(GmU$? zhU#h?gBB!^I3N-d4nQRKinxSCN&s<#6DW%WWFZm=PDn_IEL=jQM1=6Ys{WZ7kG&zj zL67u##`W{wtFPXxu6os5v!86PuzQ_(3!nE`*4Lh#3r|eVTN8I$mJ~u!@r^!-h(u4s z_GUMXx7Yl@-kiI~UgEK>g_gY=UD4x>taW2I@f1&#Cq**vbsLFnH6qdSqww>-3PtSo zM36?@i$dX{JWWiC;=iKYY4!W1j_Oy%K*hj84BTp+n4g=a+NsG2_P*OM9MrHXuNbHp zs2Hdis2Hdis2Hdis2Hdi_#b3I^>4PmgmJw!8{22H@3)M6zn*=%S^4%z{lByNBrCr* zQvcdW|FfBbT+hF<`n{~*4@TZ@X)VxVH6VxVH6VxVH6VxVH6 zVxVH6VxVH6VqgpdeqdR2rhbtQ(zyT6&;PF-LmBW_;FrL&z|+7}z@xw;z%H-@cz^@k z2K?hT%eoG{2>cd!9{3ILZD0pTfd*g$Gr+62TGlJTkANQnj{}bZp8)Oz{{C*r1HKPD z04xEoyvwq#0?z^80u=Bu;G@7S-~cx8(mO5dr@$59yFdtZf%^dqc)ey>zW}}roC02c zhh_Z}xC%T6d=+Q`9|B&w1#N+!178Qu10Mjc-E3J;0#5)JfKA|b;Jv^f-fmgH2c8BV z1s(w&1TF#Z2VS_zvc3sC4y*vT052fXaRo?#2Y?R(cLA>=-*Fwd0$c>90h+VF{TB(4 zTCLXWd#y;MfhPjIi=pJ6y|BSmvzOk-BjwkXSQkpaezD>!8Gf!FeAWwl>GbqTYkcSX zV}C2+=--SL??~OXZdx}QEa8fwJL}6(NTvka;wHAc`(<{{5SwQ5l@)C@KB**a%PeY95jEh|D{1q1u=R^ zMA$%6NM%zG9V+Zob)s~?6yISTxPjzkG-f6UlYZp4c#p@5wWa96OX5VxgeD0@LP(=w zAMK-Mu=&DaI9#nIwaNspNB%=|Z7X4GkITKVCnzMyPmXQ^gj{Bb0gkB=ZRity&d5zE zAUbr4L$bS;AG{##!fR6h}wlAbaVB-RhOmx0KvqHR){APX~CwE1>)B; z-t)LV3&xu(7wQNk?jT%593=JWnM^(+7k1bD6tPMzpt#?PJha;3GJ($}u1j;awzypH zB^|St*b80m2V6Rd@_YSE#6gargV$K8Ctoumwh}IPv{P$0FtIuip0oxb9&5D@H_MiX zFppr&`IMHE7?uSC6oDZGwPsq#5Y%eX5YBWIJ=3Q~N+b(;Zb2-TihoJVOaTMjN3?6e-u(PGgyjLbUv zX)wZwnUbT7yf6-qOAa%E1sw}lYnw|?ay)?GHx!03@gK34pK$W=VfUPR6CYahho!Kw zpXKJNy}Y`3VPkCVekpIllqr&;V-^u8mDlP@5evj_q5{`7|G93W5T$z*vaM~`jRl@w z#Ds2>hOxTmBc9Shufy0w14uX^$WIcbc_%2xe^|#vE2Q;^77i_g?S`t$`od6d7L~-) zHoigQYHI?PEz*uRE;P%P6cqOPl_ele92-mbe{gbAy06vq7H zX&9*$zhAdXchJr0aX=4Hy(-W@s>_+)C1ESlr(H^q_XIr`tjktSa+OL%u^*XX6+5cI zmsjnDW*n-JUS{R>p4azP*Hgl4hY>fMqnPiqa%?cZc<;5YH(O(+g0%5{z)BrcS#*Ng zeJ*cc#7OHQ;mz$}Q*sWrAcv$6+dEXP4F;#9>LIXRn!A!lD%|W!dQt?1+-X)yW_rHH zw9^W1C_guKP^6KlYmAkpjro?-UN~?ITM$&XJ#<$0wI8B%HQR9SXEU$KOvIYC27j4f z^QDh1I-a}r+<*F1q@%XbRcvgqxDC2T5iTXcnhh#9infG^1|lac9X7$%A7L=86|qL{ zKfL5o6WZ5n!^l=fE>62evsoN={bI8WR~?E8SU#le88@lVV=yX6*t#1mM~Mfe%H-^8B1bJZPLd!7zdf`{dO{N3ey>-0cVp%aijRp08P`Tr{L3_xf8PXqS?Gr%1Ho%MeP{22HOa1OW|I0oDV{0Zmxp8#~Oe-?NG_zu8< zyMRC9EdM>=G2k1(4zLcK2aW+R!=}Fge+GUBTmzm5$kty0)u&>hVxVH6VxVH6VxVH6 zVxVH+|DA!$gGq|)P=jOJNZNw3g}4|{IFBb?5e3D`Y+MFEOZ-z>#|y%C+caiKi6Gb0 z#f42N23HRz4cGR!5}jk#J*L@0*+?gH1Ciq1s4T<@Y}Pq}42v;r@?q8sqbRhIp`Mt; zxlEg@Q&l($_9btHl#Q;>&zc(;bJ{E|JkI9$i5vAoZp$fhRbDnKowCxSG}kC#=|Ht6 z$)#_A*p8DpI^k?g$@}b*iKC}xeYuj*t$@igjq73!-yU#Zwz}pLL6byNS}Vs(sXpZ1 znaxy!t17+|iZs!*VUXZfn?vPw)Q3vWu(@e_!KDAG*=5F&&cX?FM5<|RFSJ9MC`i{@ z2IS`Tr6kJ1=A}cu7!kS8M(qr>+#5>U542g!garc@52qxIa%3HmI85}NW7=*bF@bv+ z?MMfZ22!$N((nvx`8dkaWhHiLKsjD^`ZU|px*X_2jz!b?#*EwINFwYrFV{cB<00ma RwMC0I)>sA6c_^Q>{sZ)_N_hYP literal 0 HcmV?d00001 diff --git a/src/localization_module_lio_locus/src/lio_locus/CMakeLists.txt b/src/localization_module_lio_locus/src/lio_locus/CMakeLists.txt new file mode 100755 index 0000000..5cb2bed --- /dev/null +++ b/src/localization_module_lio_locus/src/lio_locus/CMakeLists.txt @@ -0,0 +1,58 @@ +add_library(${PROJECT_NAME} SHARED lio_locus.cpp) + +target_link_libraries(${PROJECT_NAME} + point_cloud_odometry + point_cloud_localization + point_cloud_mapper + boost_filesystem + glog + ${PCL_LIBRARIES} + pcl_common + ${YAML_CPP_LIBRARIES} +) + +ament_target_dependencies(${PROJECT_NAME} + pcl_conversions +) + +install(TARGETS ${PROJECT_NAME} + DESTINATION lib +) + +#------------------------------------------------------- + +add_library(cloud_pre_processor SHARED cloud_pre_processor.cpp) +target_link_libraries(cloud_pre_processor + pcl_filters + pcl_features + boost_filesystem + glog + ${YAML_CPP_LIBRARIES}) + +ament_target_dependencies(cloud_pre_processor + sensor_msgs + pcl_conversions + tf2 +) + + +install(TARGETS cloud_pre_processor + DESTINATION lib +) + +#------------------------------------------------------- +add_library(complementary_filter SHARED + complementary_filter.cpp +) + +target_link_libraries(complementary_filter + glog +) + +install(TARGETS complementary_filter + DESTINATION lib +) + + + + diff --git a/src/localization_module_lio_locus/src/lio_locus/cloud_pre_processor.cpp b/src/localization_module_lio_locus/src/lio_locus/cloud_pre_processor.cpp new file mode 100755 index 0000000..3b3e54b --- /dev/null +++ b/src/localization_module_lio_locus/src/lio_locus/cloud_pre_processor.cpp @@ -0,0 +1,234 @@ +/* + * cloud_pre_processor.cpp + * + * Created on: Oct 17, 2025 + * Author: solomon + */ + +/* + * test for trials + * + */ + +#include "lio_locus/cloud_pre_processor.h" + +CloudPreProcessor::CloudPreProcessor() { + google::SetStderrLogging(google::GLOG_WARNING); + FLAGS_colorlogtostderr = true; + FLAGS_alsologtostderr = true; +} + +CloudPreProcessor::~CloudPreProcessor() { +} + +// cloud format adaption: only xyzi curvature for time difference; +pcl::PointCloud::Ptr CloudPreProcessor::adaptCloudForm( + const sensor_msgs::msg::PointCloud2 &cloud_input) { + + // container to store all points transformed; + pcl::PointCloud::Ptr cloud_raw( + new pcl::PointCloud()); + + // raw ROS msg for data conversion; + pcl::PointCloud cloud_rs; + pcl::fromROSMsg(cloud_input, cloud_rs); + + // timestamp update for original cloud; + for (int k = 0; k < cloud_rs.size(); k++) { + auto pnt = cloud_rs[k]; + pcl::PointXYZINormal p_xyzi_n; + p_xyzi_n.x = pnt.x; + p_xyzi_n.y = pnt.y; + p_xyzi_n.z = pnt.z; + p_xyzi_n.intensity = pnt.intensity; + p_xyzi_n.curvature = pnt.timestamp - cloud_input.header.stamp.sec; + cloud_raw->points.push_back(p_xyzi_n); + } + + LOG(INFO) << "... cloud size after format adaption -> #[" << cloud_raw->points.size() << "]"; + + // convert ROS message time stamp to pcl timestamp; + pcl_conversions::toPCL(cloud_input.header.stamp, cloud_raw->header.stamp); + + return cloud_raw; +} + +pcl::PointCloud::Ptr CloudPreProcessor::adaptCloudFormFromLivoxCloud( + const sensor_msgs::msg::PointCloud2 &cloud_input) { + + // ROS cloud to PCL format; + pcl::PointCloud cloud_livox; + pcl::fromROSMsg(cloud_input, cloud_livox); + + // to PCL standard format: {x,y,z,intensity, line, tag, timestamp}; + pcl::PointCloud::Ptr cloud_raw( + new pcl::PointCloud()); + for (int k = 0; k < cloud_livox.size(); k++) { + livox_lidar::Point pnt = cloud_livox[k]; + pcl::PointXYZINormal p_xyzi_n; + p_xyzi_n.x = pnt.x; + p_xyzi_n.y = pnt.y; + p_xyzi_n.z = pnt.z; + p_xyzi_n.intensity = pnt.intensity; + p_xyzi_n.curvature = pnt.timestamp; + cloud_raw->points.push_back(p_xyzi_n); + } + pcl_conversions::toPCL(cloud_input.header.stamp, cloud_raw->header.stamp); + + LOG(INFO) << "... cloud size after format adaption -> #[" << cloud_raw->points.size() << "]"; + + return cloud_raw; +} + +// transform coordinates of cloud based on input static transformation matrix; +pcl::PointCloud::Ptr CloudPreProcessor::transformCloudCartesian( + pcl::PointCloud::Ptr cloud_input, + tf2::Transform T) { + + pcl::PointCloud::Ptr cloud_out( + new pcl::PointCloud()); + + cloud_out->points.reserve(cloud_input->points.size()); + for (int k = 0; k < cloud_input->points.size(); k++) { + + pcl::PointXYZINormal pnt_raw = cloud_input->points[k]; + tf2::Vector3 pnt = T * tf2::Vector3(pnt_raw.x, pnt_raw.y, pnt_raw.z); + + pcl::PointXYZINormal p_xyzi_n; + p_xyzi_n.x = pnt.x(); + p_xyzi_n.y = pnt.y(); + p_xyzi_n.z = pnt.z(); + p_xyzi_n.intensity = pnt_raw.intensity; + p_xyzi_n.curvature = pnt_raw.curvature; + + cloud_out->points.push_back(p_xyzi_n); + } + + cloud_out->header.stamp = cloud_input->header.stamp; + + return cloud_out; +} + +bool CloudPreProcessor::doVoxelGridFilteringAndComputeNormals( + pcl::PointCloud::Ptr input, + pcl::PointCloud::Ptr &cloud_normals) { + + // basic statistics about node; + LOG(INFO) << "####################################################"; + LOG(INFO) << " CLOUD PRE-PROCESSOR "; + LOG(INFO) << "####################################################"; + + if (input == nullptr) + return false; + + if (cloud_normals == nullptr) { + cloud_normals = pcl::PointCloud::Ptr( + new pcl::PointCloud()); + } + + auto start_chrono = std::chrono::steady_clock::now(); + + //------------------------------------------------------------------------ + // voxel grid filtering; + //------------------------------------------------------------------------ + boost::mutex::scoped_lock lock(mutex_); + + pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2()); + pcl::toPCLPointCloud2(*input, *pcl_input); + + static pcl::VoxelGrid impl_; + static bool flag_init = false; + if (!flag_init) { + impl_.setLeafSize(leaf_voxel_filtering_, leaf_voxel_filtering_, + leaf_voxel_filtering_); + impl_.setFilterLimits(filter_limit_, filter_limit_); + impl_.setFilterLimitsNegative(false); + + flag_init = true; + } + + impl_.setInputCloud(pcl_input); + pcl::PCLPointCloud2 pcl_output; + impl_.filter(pcl_output); + + pcl::PointCloud::Ptr cloud_xyzi( + new pcl::PointCloud()); + pcl::fromPCLPointCloud2(pcl_output, *cloud_xyzi); + //---------------------------------------------------------------------------------- + static pcl::NormalEstimationOMP normal_estimator = + pcl::NormalEstimationOMP(size_cores_); + static bool flag_init_ne = false; + if (!flag_init_ne) { + pcl::search::KdTree::Ptr tree( + new pcl::search::KdTree()); + normal_estimator.setSearchMethod(tree); + normal_estimator.setKSearch(size_k_search_); + normal_estimator.setRadiusSearch(radius_search_); + + flag_init_ne = true; + } + + normal_estimator.setInputCloud(cloud_xyzi); + pcl::PointCloud::Ptr normals( + new pcl::PointCloud()); + normal_estimator.compute(*normals); + + // assign normal vector to points; + for (size_t i = 0; i < cloud_xyzi->points.size(); i++) { + pcl::PointXYZINormal point; + + auto pnt = cloud_xyzi->points[i]; + point.x = pnt.x; + point.y = pnt.y; + point.z = pnt.z; + point.intensity = pnt.intensity; + + pcl::Normal normal = normals->points[i]; + point.normal_x = normal.normal_x; + point.normal_y = normal.normal_y; + point.normal_z = normal.normal_z; + + cloud_normals->points.push_back(point); + } + cloud_normals->header.stamp = input->header.stamp; + + //------------------------------------------------------------------------- + auto end_chrono = std::chrono::steady_clock::now(); + double dt_chrono = std::chrono::duration(end_chrono - start_chrono).count(); + LOG(INFO) + << "... time passed for cloud voxel filtering and normal calculation: [" + << dt_chrono * 1e3 << "] ms"; + + return true; +} + +// attention of things of interest; +bool CloudPreProcessor::transformCloudWithNormalCalculation( + pcl::PointCloud::Ptr cloud_input, + tf2::Transform T, + pcl::PointCloud::Ptr &cloud_normals) { + + auto ts_start = std::chrono::steady_clock::now(); + + uint64_t ts = cloud_input->header.stamp; + pcl::PointCloud::Ptr cloud_raw_trans = + transformCloudCartesian(cloud_input, T); + + cloud_normals = pcl::PointCloud::Ptr( + new pcl::PointCloud()); + + bool flag = false; + + if (doVoxelGridFilteringAndComputeNormals(cloud_raw_trans, cloud_normals)) { + flag = true; + } + + auto ts_end = std::chrono::steady_clock::now(); + double dt = std::chrono::duration(ts_end - ts_start).count(); + + LOG(INFO) << "... dt for cloud pre-processing -> #[" << dt * 1e3 << "]"; + + writeDt2LogFile(path_log, "log_dt_ms_cloud_preprocessing.txt", dt * 1e3); + + return false; +} \ No newline at end of file diff --git a/src/localization_module_lio_locus/src/lio_locus/complementary_filter.cpp b/src/localization_module_lio_locus/src/lio_locus/complementary_filter.cpp new file mode 100755 index 0000000..8af9da5 --- /dev/null +++ b/src/localization_module_lio_locus/src/lio_locus/complementary_filter.cpp @@ -0,0 +1,543 @@ +/* + @author Roberto G. Valenti + + @section LICENSE + Copyright (c) 2015, City University of New York + CCNY Robotics Lab + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. +*/ + + +#include "lio_locus/complementary_filter.h" + + +namespace imu_tools { + +const double ComplementaryFilter::kGravity = 9.81; +const double ComplementaryFilter::gamma_ = 0.01; +// Bias estimation steady state thresholds +const double ComplementaryFilter::kAngularVelocityThreshold = 0.2; +const double ComplementaryFilter::kAccelerationThreshold = 0.1; +const double ComplementaryFilter::kDeltaAngularVelocityThreshold = 0.01; + +ComplementaryFilter::ComplementaryFilter() + : gain_acc_(0.01), + gain_mag_(0.01), + bias_alpha_(0.01), + do_bias_estimation_(true), + do_adaptive_gain_(false), + initialized_(false), + steady_state_(false), + q0_(1), + q1_(0), + q2_(0), + q3_(0), + wx_prev_(0), + wy_prev_(0), + wz_prev_(0), + wx_bias_(0), + wy_bias_(0), + wz_bias_(0) +{ +} + +ComplementaryFilter::~ComplementaryFilter() = default; + +void ComplementaryFilter::setDoBiasEstimation(bool do_bias_estimation) +{ + do_bias_estimation_ = do_bias_estimation; +} + +bool ComplementaryFilter::getDoBiasEstimation() const +{ + return do_bias_estimation_; +} + +void ComplementaryFilter::setDoAdaptiveGain(bool do_adaptive_gain) +{ + do_adaptive_gain_ = do_adaptive_gain; +} + +bool ComplementaryFilter::getDoAdaptiveGain() const +{ + return do_adaptive_gain_; +} + +bool ComplementaryFilter::setGainAcc(double gain) +{ + if (gain >= 0 && gain <= 1.0) + { + gain_acc_ = gain; + return true; + } else + return false; +} +bool ComplementaryFilter::setGainMag(double gain) +{ + if (gain >= 0 && gain <= 1.0) + { + gain_mag_ = gain; + return true; + } else + return false; +} + +double ComplementaryFilter::getGainAcc() const +{ + return gain_acc_; +} + +double ComplementaryFilter::getGainMag() const +{ + return gain_mag_; +} + +bool ComplementaryFilter::getSteadyState() const +{ + return steady_state_; +} + +bool ComplementaryFilter::setBiasAlpha(double bias_alpha) +{ + if (bias_alpha >= 0 && bias_alpha <= 1.0) + { + bias_alpha_ = bias_alpha; + return true; + } else + return false; +} + +double ComplementaryFilter::getBiasAlpha() const +{ + return bias_alpha_; +} + +void ComplementaryFilter::setOrientation(double q0, double q1, double q2, + double q3) +{ + // Set the state to inverse (state is fixed wrt body). + invertQuaternion(q0, q1, q2, q3, q0_, q1_, q2_, q3_); +} + +double ComplementaryFilter::getAngularVelocityBiasX() const +{ + return wx_bias_; +} + +double ComplementaryFilter::getAngularVelocityBiasY() const +{ + return wy_bias_; +} + +double ComplementaryFilter::getAngularVelocityBiasZ() const +{ + return wz_bias_; +} + +void ComplementaryFilter::update(double ax, double ay, double az, double wx, + double wy, double wz, double dt) +{ + + auto ts_start = std::chrono::steady_clock::now(); + + if (!initialized_) + { + // First time - ignore prediction: + getMeasurement(ax, ay, az, q0_, q1_, q2_, q3_); + initialized_ = true; + return; + } + + // Bias estimation. + if (do_bias_estimation_) updateBiases(ax, ay, az, wx, wy, wz); + + // Prediction. + double q0_pred, q1_pred, q2_pred, q3_pred; + getPrediction(wx, wy, wz, dt, q0_pred, q1_pred, q2_pred, q3_pred); + + // Correction (from acc): + // q_ = q_pred * [(1-gain) * qI + gain * dq_acc] + // where qI = identity quaternion + double dq0_acc, dq1_acc, dq2_acc, dq3_acc; + getAccCorrection(ax, ay, az, q0_pred, q1_pred, q2_pred, q3_pred, dq0_acc, + dq1_acc, dq2_acc, dq3_acc); + + double gain; + if (do_adaptive_gain_) + { + gain = getAdaptiveGain(gain_acc_, ax, ay, az); + + } else + { + gain = gain_acc_; + } + + scaleQuaternion(gain, dq0_acc, dq1_acc, dq2_acc, dq3_acc); + + quaternionMultiplication(q0_pred, q1_pred, q2_pred, q3_pred, dq0_acc, + dq1_acc, dq2_acc, dq3_acc, q0_, q1_, q2_, q3_); + + normalizeQuaternion(q0_, q1_, q2_, q3_); + + auto ts_end = std::chrono::steady_clock::now(); + double dt_dura = std::chrono::duration(ts_end - ts_start).count(); + + LOG(INFO) << "... inside dt -> [" << dt_dura * 1e3 << "]"; + + writeDt2LogFile(path_log, "log_dt_ms_imu_preprocessing.txt", dt_dura * 1e3); +} + +void ComplementaryFilter::update(double ax, double ay, double az, double wx, + double wy, double wz, double mx, double my, + double mz, double dt) +{ + if (!initialized_) + { + // First time - ignore prediction: + getMeasurement(ax, ay, az, mx, my, mz, q0_, q1_, q2_, q3_); + initialized_ = true; + return; + } + + // Bias estimation. + if (do_bias_estimation_) updateBiases(ax, ay, az, wx, wy, wz); + + // Prediction. + double q0_pred, q1_pred, q2_pred, q3_pred; + getPrediction(wx, wy, wz, dt, q0_pred, q1_pred, q2_pred, q3_pred); + + // Correction (from acc): + // q_temp = q_pred * [(1-gain) * qI + gain * dq_acc] + // where qI = identity quaternion + double dq0_acc, dq1_acc, dq2_acc, dq3_acc; + getAccCorrection(ax, ay, az, q0_pred, q1_pred, q2_pred, q3_pred, dq0_acc, + dq1_acc, dq2_acc, dq3_acc); + double alpha = gain_acc_; + if (do_adaptive_gain_) alpha = getAdaptiveGain(gain_acc_, ax, ay, az); + scaleQuaternion(alpha, dq0_acc, dq1_acc, dq2_acc, dq3_acc); + + double q0_temp, q1_temp, q2_temp, q3_temp; + quaternionMultiplication(q0_pred, q1_pred, q2_pred, q3_pred, dq0_acc, + dq1_acc, dq2_acc, dq3_acc, q0_temp, q1_temp, + q2_temp, q3_temp); + + // Correction (from mag): + // q_ = q_temp * [(1-gain) * qI + gain * dq_mag] + // where qI = identity quaternion + double dq0_mag, dq1_mag, dq2_mag, dq3_mag; + getMagCorrection(mx, my, mz, q0_temp, q1_temp, q2_temp, q3_temp, dq0_mag, + dq1_mag, dq2_mag, dq3_mag); + + scaleQuaternion(gain_mag_, dq0_mag, dq1_mag, dq2_mag, dq3_mag); + + quaternionMultiplication(q0_temp, q1_temp, q2_temp, q3_temp, dq0_mag, + dq1_mag, dq2_mag, dq3_mag, q0_, q1_, q2_, q3_); + + normalizeQuaternion(q0_, q1_, q2_, q3_); +} + +bool ComplementaryFilter::checkState(double ax, double ay, double az, double wx, + double wy, double wz) const +{ + double acc_magnitude = sqrt(ax * ax + ay * ay + az * az); + if (fabs(acc_magnitude - kGravity) > kAccelerationThreshold) return false; + + if (fabs(wx - wx_prev_) > kDeltaAngularVelocityThreshold || + fabs(wy - wy_prev_) > kDeltaAngularVelocityThreshold || + fabs(wz - wz_prev_) > kDeltaAngularVelocityThreshold) + return false; + + if (fabs(wx - wx_bias_) > kAngularVelocityThreshold || + fabs(wy - wy_bias_) > kAngularVelocityThreshold || + fabs(wz - wz_bias_) > kAngularVelocityThreshold) + return false; + + return true; +} + +void ComplementaryFilter::updateBiases(double ax, double ay, double az, + double wx, double wy, double wz) +{ + steady_state_ = checkState(ax, ay, az, wx, wy, wz); + + if (steady_state_) + { + wx_bias_ += bias_alpha_ * (wx - wx_bias_); + wy_bias_ += bias_alpha_ * (wy - wy_bias_); + wz_bias_ += bias_alpha_ * (wz - wz_bias_); + } + + wx_prev_ = wx; + wy_prev_ = wy; + wz_prev_ = wz; +} + +void ComplementaryFilter::getPrediction(double wx, double wy, double wz, + double dt, double& q0_pred, + double& q1_pred, double& q2_pred, + double& q3_pred) const +{ + double wx_unb = wx - wx_bias_; + double wy_unb = wy - wy_bias_; + double wz_unb = wz - wz_bias_; + + q0_pred = q0_ + 0.5 * dt * (wx_unb * q1_ + wy_unb * q2_ + wz_unb * q3_); + q1_pred = q1_ + 0.5 * dt * (-wx_unb * q0_ - wy_unb * q3_ + wz_unb * q2_); + q2_pred = q2_ + 0.5 * dt * (wx_unb * q3_ - wy_unb * q0_ - wz_unb * q1_); + q3_pred = q3_ + 0.5 * dt * (-wx_unb * q2_ + wy_unb * q1_ - wz_unb * q0_); + + normalizeQuaternion(q0_pred, q1_pred, q2_pred, q3_pred); +} + +void ComplementaryFilter::getMeasurement(double ax, double ay, double az, + double mx, double my, double mz, + double& q0_meas, double& q1_meas, + double& q2_meas, double& q3_meas) +{ + // q_acc is the quaternion obtained from the acceleration vector + // representing the orientation of the Global frame wrt the Local frame with + // arbitrary yaw (intermediary frame). q3_acc is defined as 0. + double q0_acc, q1_acc, q2_acc, q3_acc; + + // Normalize acceleration vector. + normalizeVector(ax, ay, az); + if (az >= 0) + { + q0_acc = sqrt((az + 1) * 0.5); + q1_acc = -ay / (2.0 * q0_acc); + q2_acc = ax / (2.0 * q0_acc); + q3_acc = 0; + } else + { + double X = sqrt((1 - az) * 0.5); + q0_acc = -ay / (2.0 * X); + q1_acc = X; + q2_acc = 0; + q3_acc = ax / (2.0 * X); + } + + // [lx, ly, lz] is the magnetic field reading, rotated into the intermediary + // frame by the inverse of q_acc. + // l = R(q_acc)^-1 m + double lx = (q0_acc * q0_acc + q1_acc * q1_acc - q2_acc * q2_acc) * mx + + 2.0 * (q1_acc * q2_acc) * my - 2.0 * (q0_acc * q2_acc) * mz; + double ly = 2.0 * (q1_acc * q2_acc) * mx + + (q0_acc * q0_acc - q1_acc * q1_acc + q2_acc * q2_acc) * my + + 2.0 * (q0_acc * q1_acc) * mz; + + // q_mag is the quaternion that rotates the Global frame (North West Up) + // into the intermediary frame. q1_mag and q2_mag are defined as 0. + double gamma = lx * lx + ly * ly; + double beta = sqrt(gamma + lx * sqrt(gamma)); + double q0_mag = beta / (sqrt(2.0 * gamma)); + double q3_mag = ly / (sqrt(2.0) * beta); + + // The quaternion multiplication between q_acc and q_mag represents the + // quaternion, orientation of the Global frame wrt the local frame. + // q = q_acc times q_mag + quaternionMultiplication(q0_acc, q1_acc, q2_acc, q3_acc, q0_mag, 0, 0, + q3_mag, q0_meas, q1_meas, q2_meas, q3_meas); + // q0_meas = q0_acc*q0_mag; + // q1_meas = q1_acc*q0_mag + q2_acc*q3_mag; + // q2_meas = q2_acc*q0_mag - q1_acc*q3_mag; + // q3_meas = q0_acc*q3_mag; +} + +void ComplementaryFilter::getMeasurement(double ax, double ay, double az, + double& q0_meas, double& q1_meas, + double& q2_meas, double& q3_meas) +{ + // q_acc is the quaternion obtained from the acceleration vector + // representing the orientation of the Global frame wrt the Local frame with + // arbitrary yaw (intermediary frame). q3_acc is defined as 0. + + // Normalize acceleration vector. + normalizeVector(ax, ay, az); + + if (az >= 0) + { + q0_meas = sqrt((az + 1) * 0.5); + q1_meas = -ay / (2.0 * q0_meas); + q2_meas = ax / (2.0 * q0_meas); + q3_meas = 0; + } else + { + double X = sqrt((1 - az) * 0.5); + q0_meas = -ay / (2.0 * X); + q1_meas = X; + q2_meas = 0; + q3_meas = ax / (2.0 * X); + } +} + +void ComplementaryFilter::getAccCorrection(double ax, double ay, double az, + double p0, double p1, double p2, + double p3, double& dq0, double& dq1, + double& dq2, double& dq3) +{ + // Normalize acceleration vector. + normalizeVector(ax, ay, az); + + // Acceleration reading rotated into the world frame by the inverse + // predicted quaternion (predicted gravity): + double gx, gy, gz; + rotateVectorByQuaternion(ax, ay, az, p0, -p1, -p2, -p3, gx, gy, gz); + + // Delta quaternion that rotates the predicted gravity into the real + // gravity: + dq0 = sqrt((gz + 1) * 0.5); + dq1 = -gy / (2.0 * dq0); + dq2 = gx / (2.0 * dq0); + dq3 = 0.0; +} + +void ComplementaryFilter::getMagCorrection(double mx, double my, double mz, + double p0, double p1, double p2, + double p3, double& dq0, double& dq1, + double& dq2, double& dq3) +{ + // Magnetic reading rotated into the world frame by the inverse predicted + // quaternion: + double lx, ly, lz; + rotateVectorByQuaternion(mx, my, mz, p0, -p1, -p2, -p3, lx, ly, lz); + + // Delta quaternion that rotates the l so that it lies in the xz-plane + // (points north): + double gamma = lx * lx + ly * ly; + double beta = sqrt(gamma + lx * sqrt(gamma)); + dq0 = beta / (sqrt(2.0 * gamma)); + dq1 = 0.0; + dq2 = 0.0; + dq3 = ly / (sqrt(2.0) * beta); +} + +void ComplementaryFilter::getOrientation(double& q0, double& q1, double& q2, + double& q3) const +{ + // Return the inverse of the state (state is fixed wrt body). + invertQuaternion(q0_, q1_, q2_, q3_, q0, q1, q2, q3); +} + +double ComplementaryFilter::getAdaptiveGain(double alpha, double ax, double ay, + double az) +{ + double a_mag = sqrt(ax * ax + ay * ay + az * az); + double error = fabs(a_mag - kGravity) / kGravity; + double factor; + double error1 = 0.1; + double error2 = 0.2; + double m = 1.0 / (error1 - error2); + double b = 1.0 - m * error1; + if (error < error1) + factor = 1.0; + else if (error < error2) + factor = m * error + b; + else + factor = 0.0; + // printf("FACTOR: %f \n", factor); + return factor * alpha; +} + +void normalizeVector(double& x, double& y, double& z) +{ + double norm = sqrt(x * x + y * y + z * z); + + x /= norm; + y /= norm; + z /= norm; +} + +void normalizeQuaternion(double& q0, double& q1, double& q2, double& q3) +{ + double norm = sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 /= norm; + q1 /= norm; + q2 /= norm; + q3 /= norm; +} + +void invertQuaternion(double q0, double q1, double q2, double q3, + double& q0_inv, double& q1_inv, double& q2_inv, + double& q3_inv) +{ + // Assumes quaternion is normalized. + q0_inv = q0; + q1_inv = -q1; + q2_inv = -q2; + q3_inv = -q3; +} + +void scaleQuaternion(double gain, double& dq0, double& dq1, double& dq2, + double& dq3) +{ + if (dq0 < 0.0) // 0.9 + { + // Slerp (Spherical linear interpolation): + double angle = acos(dq0); + double A = sin(angle * (1.0 - gain)) / sin(angle); + double B = sin(angle * gain) / sin(angle); + dq0 = A + B * dq0; + dq1 = B * dq1; + dq2 = B * dq2; + dq3 = B * dq3; + } else + { + // Lerp (Linear interpolation): + dq0 = (1.0 - gain) + gain * dq0; + dq1 = gain * dq1; + dq2 = gain * dq2; + dq3 = gain * dq3; + } + + normalizeQuaternion(dq0, dq1, dq2, dq3); +} + +void quaternionMultiplication(double p0, double p1, double p2, double p3, + double q0, double q1, double q2, double q3, + double& r0, double& r1, double& r2, double& r3) +{ + // r = p q + r0 = p0 * q0 - p1 * q1 - p2 * q2 - p3 * q3; + r1 = p0 * q1 + p1 * q0 + p2 * q3 - p3 * q2; + r2 = p0 * q2 - p1 * q3 + p2 * q0 + p3 * q1; + r3 = p0 * q3 + p1 * q2 - p2 * q1 + p3 * q0; +} + +void rotateVectorByQuaternion(double x, double y, double z, double q0, + double q1, double q2, double q3, double& vx, + double& vy, double& vz) +{ + vx = (q0 * q0 + q1 * q1 - q2 * q2 - q3 * q3) * x + + 2 * (q1 * q2 - q0 * q3) * y + 2 * (q1 * q3 + q0 * q2) * z; + vy = 2 * (q1 * q2 + q0 * q3) * x + + (q0 * q0 - q1 * q1 + q2 * q2 - q3 * q3) * y + + 2 * (q2 * q3 - q0 * q1) * z; + vz = 2 * (q1 * q3 - q0 * q2) * x + 2 * (q2 * q3 + q0 * q1) * y + + (q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3) * z; +} + +} // namespace imu_tools diff --git a/src/localization_module_lio_locus/src/lio_locus/lio_locus.cpp b/src/localization_module_lio_locus/src/lio_locus/lio_locus.cpp new file mode 100755 index 0000000..536c0ec --- /dev/null +++ b/src/localization_module_lio_locus/src/lio_locus/lio_locus.cpp @@ -0,0 +1,590 @@ +/* + * lio_locus.cpp + * + * Created on: Sep 11, 2025 + * Author: solomon + */ + +#include "lio_locus/lio_locus.h" + +namespace lio_locus { + +LioLocus::LioLocus() { + google::SetStderrLogging(google::GLOG_WARNING); + FLAGS_colorlogtostderr = true; + FLAGS_alsologtostderr = true; +} + +LioLocus::~LioLocus() { +} + +void LioLocus::setPath2Parameters(string path_to_param) { + m_path_to_file = path_to_param; + + LOG(INFO) << "path to parameter file -> [" << m_path_to_file << "]"; +} + +bool LioLocus::initialize(string path_to_param) { + + mp_cloud_incremental = PointCloudType::Ptr(new PointCloudType()); + + setPath2Parameters(path_to_param); + + mp_cloud_odometry = PointCloudOdometryPtr(new PointCloudOdometry()); + mp_cloud_odometry->Initialize(m_path_to_file); + mp_cloud_odometry->EnableImuIntegration(); + +// mp_cloud_mapper = (PointCloudMapperPtr) (new PointCloudMapper()); +// mp_cloud_mapper = (PointCloudMultiThreadedMapperPtr) (new Point CloudMultiThreadedMapper()); + + mp_cloud_mapper = PointCloudIkdTreeMapperPtr(new PointCloudIkdTreeMapper()); + mp_cloud_mapper->Initialize(m_path_to_file); + + mp_cloud_localization = PointCloudLocalizationPtr( + new PointCloudLocalization()); + mp_cloud_localization->Initialize(m_path_to_file); + + return false; +} + +// normal tracking and updating the cloud map in memory; +void LioLocus::trackCurrentCloudWithOnlineBuiltMap( + PointCloudType::Ptr msg_cloud) { + + auto ts_start = std::chrono::steady_clock::now(); + + // associate timestamp with pose; + std::uint64_t timestamp_now = msg_cloud->header.stamp; // uint64_t; + + auto start_chrono = std::chrono::steady_clock::now(); + LOG(INFO) << "####################################################"; + LOG(INFO) << " LIO-LOCUS "; + LOG(INFO) << "####################################################"; + + if (!mb_tracker_reset) { // normal case; + + //--------------------------------------------------------------- + // 0. set delta transform prior; + //--------------------------------------------------------------- + geometry_utils::Transform3 dT_prior_gu = + geometry_utils::Transform3::Identity(); + + //------------------------------------------------------ + // 1. get delta transformation from sensor observations; + //------------------------------------------------------ + // use imu orientation prior to update value for lidar odometry; + geometry_utils::Quaterniond dq_imu; + if (mb_use_imu) { + LOG(INFO) << "... a. getting prior from gyro observations ... "; + + auto time = pcl_conversions::fromPCL(msg_cloud->header.stamp); + + getRelativeRotationFromIMU(time.seconds(), dq_imu); + + // TODO: update rotation in prior dT; + dT_prior_gu.rotation = dq_imu; + + } // end of scope for imu gyro prior assignment; + + //--------------------------------------------------------------- + // 2. estimate increments using scan-to-scan lidar odmoetry; + //--------------------------------------------------------------- + + LOG(INFO) << "... a. get relative displacement from sensors ..."; + LOG(INFO) << "... translation -> #[" << dT_prior_gu.translation.X() + << "," << dT_prior_gu.translation.Y() << "," + << dT_prior_gu.translation.Z() << "] and angles ->[" + << dT_prior_gu.rotation.Roll() << "," + << dT_prior_gu.rotation.Pitch() << "," + << dT_prior_gu.rotation.Yaw() << "]"; + + if (mb_use_scan2scan_matching) { + LOG(INFO) + << "... b. estimating lidar odometry for consecutive scan matching! ... "; + // set imu prior to be later used in lidar odometry scan matching; + mp_cloud_odometry->EnableImuIntegration(); + mp_cloud_odometry->SetImuDelta(toRotationMatrix(dq_imu)); + mp_cloud_odometry->DisableSensorIntegration(); + + mp_cloud_odometry->SetLidar(*msg_cloud); + + if (!mp_cloud_odometry->UpdateEstimate()) { + LOG(INFO) + << "... cloud odometry fails in state estimation!"; + //TODO ... more when scan-to-scan matching fails; + + return;// now directly skip processing; + } + + geometry_utils::Transform3 dT_scan2scan = + mp_cloud_odometry->GetIncrementalEstimate(); + dT_prior_gu = dT_scan2scan; + LOG(INFO) << "... translation -> #[" + << dT_prior_gu.translation.X() << "," + << dT_prior_gu.translation.Y() << "," + << dT_prior_gu.translation.Z() << "] and angles ->[" + << dT_prior_gu.rotation.Roll() << "," + << dT_prior_gu.rotation.Pitch() << "," + << dT_prior_gu.rotation.Yaw() << "]"; + } + //--------------------------------------------------------------- + // 3. estimate pose from lidar localizer: update pose through matching against correspondences; + + // check if milestone or not; + static bool flag_ref_pose_recorded = false; + static geometry_utils::Transform3 pose_ref; + + // check displacement over thresholds; + auto current_pose = mp_cloud_localization->GetIntegratedEstimate(); + bool flag_record_cloud = false; + if (!flag_ref_pose_recorded) { + pose_ref = current_pose; + flag_ref_pose_recorded = true; + + flag_record_cloud = true; + } // record for comparing for first time; + else { + + // estimate pose through scan-map matching; + + LOG(INFO) << "... c. registering cloud to map ... "; + + // motion prior from lidar odometry; + mp_cloud_localization->MotionUpdate(dT_prior_gu); + + LOG(INFO) << "... translation -> #[" + << dT_prior_gu.translation.X() << "," + << dT_prior_gu.translation.Y() << "," + << dT_prior_gu.translation.Z() << "] and angles ->[" + << dT_prior_gu.rotation.Roll() << "," + << dT_prior_gu.rotation.Pitch() << "," + << dT_prior_gu.rotation.Yaw() << "]"; + + //---------------------------------------------------------------- + // refine pose prior within localizer; + //---------------------------------------------------------------- + // data association using euclidean distance metric; + PointCloudType::Ptr cloud_query_fixed(new PointCloudType()); + mp_cloud_localization->TransformPointsToFixedFrame(*msg_cloud, + cloud_query_fixed.get()); + PointCloudType::Ptr cloud_ref_fixed(new PointCloudType()); + if (mp_cloud_mapper->ApproxNearestNeighbors(*cloud_query_fixed, + cloud_ref_fixed.get())) { + + PointCloudType::Ptr cloud_ref_local(new PointCloudType()); + mp_cloud_localization->TransformPointsToSensorFrame( + *cloud_ref_fixed, cloud_ref_local.get()); + + // correct relative displacement through scan matching; + PointCloudType::Ptr aligned_query(new PointCloudType()); + mp_cloud_localization->MeasurementUpdate(msg_cloud, + cloud_ref_local, aligned_query.get()); + + LOG(INFO) << "... measurement update done!"; + + geometry_utils::Transform3 current_pose = + mp_cloud_localization->GetIntegratedEstimate(); + + //TODO + + // set pose of robot; + + } else { + LOG(WARNING) + << "... data association fails to find correspondences!"; + + //TODO. extends when scan-map matching fails; + + return; + } + + geometry_utils::Transform3 delta_pose = geometry_utils::PoseUpdate( + geometry_utils::PoseInverse(pose_ref), current_pose); + + // for distance more than threshold; + auto translation = delta_pose.translation; + if (std::pow(translation.X(), 2) + std::pow(translation.Y(), 2) + + std::pow(translation.Z(), 2) + > m_threshold_trans_map * m_threshold_trans_map + or std::fabs(delta_pose.rotation.Yaw()) + > m_threshold_rot_map) { + + flag_ref_pose_recorded = true; + pose_ref = current_pose; + + flag_record_cloud = true; + } + + } + + //--------------------------------------------------------------- + // 4. update map if necessary; + //--------------------------------------------------------------- + + // update cloud map when milestone is found; + if (flag_record_cloud) { + LOG(INFO) << "... #. inserting cloud to map ... "; + transformCloudAndInsertToMap(msg_cloud); + } + } // end of scope for normal tracking; + else { + + LOG(INFO) << "... resetting tracker ... "; + + if (mp_cloud_mapper->getCloudMapInMem() == nullptr) { + + LOG(INFO) << "... cloud map not ready for retrieval!"; + + return; + } + + // if required to reset, relocalize in the cloud map in memory, and break only when succeeds; + if (trackCurrentCloudWithPriorCloudMap(msg_cloud)) { + + // reset components for odometry, + mp_cloud_odometry->reset(); + LOG(INFO) + << "... #. inserting cloud to map during tracking resetting ... "; + + mb_tracker_reset = false; + } + } // end of scope for resetting case; + + auto end_chrono = std::chrono::steady_clock::now(); + double dt_chrono = + std::chrono::duration(end_chrono - start_chrono).count(); + LOG(INFO) << "... time used for cloud processing #[" << dt_chrono * 1e3 + << "]ms ... "; + + // set time stamp associated pose; + geometry_utils::Transform3 pose = + mp_cloud_localization->GetIntegratedEstimate(); + m_pose_latest = TransformStamped(pose, timestamp_now); + mp_cloud_incremental->header.stamp = timestamp_now; + + auto ts_end = std::chrono::steady_clock::now(); + auto dt = std::chrono::duration(ts_end - ts_start).count(); + + writeDt2LogFile(path_log, "log_dt_ms_lio_locus_track_online_map.txt", dt * 1e3); + +} + +void LioLocus::clearCloudMapInMemory() { + mp_cloud_mapper->Reset(); +} + +bool LioLocus::saveCloudMapInMemory(string path, bool flag_voxel_filtering, + double leaf_size) { + + boost::filesystem::path path_cloud(path); + if (!boost::filesystem::exists(path)) { + boost::filesystem::create_directory(path); + } + + string fn = "cloud_map.pcd"; + // save map from memory to disk; + PointCloudType::Ptr ptr_cloud_map(new PointCloudType()); + if (getCloudMapInMemory(ptr_cloud_map)) { + // voxel grid filter the cloud if necessary; + if (flag_voxel_filtering) { + ptr_cloud_map = downsampleCloud(ptr_cloud_map, leaf_size); + } + + // check: normal vector information ; + pcl::io::savePCDFileASCII(path + "/" + fn, *ptr_cloud_map); + + LOG(INFO) << "cloud map saved to [" << path << "] with name [" << fn + << "]"; + + return true; + } + return false; +} + +bool LioLocus::uploadPriorCloudMap(string fn_cloud_map, double leaf_size) { + + LOG(INFO) << "... check file exists -> [" + << boost::filesystem::exists(fn_cloud_map) << "] for [" + << fn_cloud_map << "]"; + if (!boost::filesystem::exists(fn_cloud_map)) { + LOG(ERROR) << "... cloud map not exists! check for cloud map!"; + return false; + } + +//-------------------------------------------------------------------- +// load cloud in PCL format; + PointCloudType::Ptr cloud_pcl(new PointCloudType()); + pcl::io::loadPCDFile(fn_cloud_map, *cloud_pcl); +//-------------------------------------------------------------------- + LOG(INFO) + << "####################################!!!!!!!!!!!!!!!!!!#####################"; + LOG(INFO) << "... #cloud map size -> [" << cloud_pcl->size() << "]"; + LOG(INFO) << "... voxel filering leaf size -> [" << leaf_size << "]"; + pcl::VoxelGrid voxel_grid_filter; + voxel_grid_filter.setLeafSize(leaf_size, leaf_size, leaf_size); + voxel_grid_filter.setInputCloud(cloud_pcl); + voxel_grid_filter.filter(*cloud_pcl); + + mp_cloud_mapper->Reset(); + + PointCloudType::Ptr unused(new PointCloudType()); + mp_cloud_mapper->InsertPoints(cloud_pcl, unused.get()); + LOG(INFO) << "# inserted cloud map size -> [" << cloud_pcl->size() + << "]"; + LOG(INFO) + << "####################################!!!!!!!!!!!!!!!!!!#####################"; + + return true; + +} + +// using prior cloud map in memory, do re-localization without updating the memory cloud map; +bool LioLocus::trackCurrentCloudWithPriorCloudMap( + PointCloudType::Ptr msg_cloud) { + + std::uint64_t timestamp_now = msg_cloud->header.stamp; // uint64_t; + + //--------------------------------------------------------------- + // 0. set delta transform prior; + //--------------------------------------------------------------- + geometry_utils::Transform3 dT_prior_gu = + geometry_utils::Transform3::Identity(); + + // update with pure lidar odometry; + + LOG(INFO) + << "... b. estimating lidar odometry for consecutive scan matching! ... "; + // set imu prior to be later used in lidar odometry scan matching; + mp_cloud_odometry->EnableImuIntegration(); + mp_cloud_odometry->SetImuDelta( + toRotationMatrix(dT_prior_gu.rotation.Yaw())); + mp_cloud_odometry->DisableSensorIntegration(); + + mp_cloud_odometry->SetLidar(*msg_cloud); + if (!mp_cloud_odometry->UpdateEstimate()) { + LOG(WARNING) << "... cloud odometry fails due to abrupt sudden!"; + //TODO ... more when scan-to-scan matching fails; + } + + geometry_utils::Transform3 dT_scan2scan = + mp_cloud_odometry->GetIncrementalEstimate(); + dT_prior_gu = dT_scan2scan; + + LOG(INFO) << "#########################################"; + LOG(INFO) << "... increment -> #[" << dT_scan2scan.translation.X() + << "," << dT_scan2scan.translation.Y() << "]"; + LOG(INFO) << "#########################################"; + + // motion prior from lidar odometry; + mp_cloud_localization->MotionUpdate(dT_prior_gu); + + // data association using euclidean distance metric; + PointCloudType::Ptr cloud_query_fixed(new PointCloudType()); + mp_cloud_localization->TransformPointsToFixedFrame(*msg_cloud, + cloud_query_fixed.get()); + PointCloudType::Ptr cloud_ref_fixed(new PointCloudType()); + if (mp_cloud_mapper->ApproxNearestNeighbors(*cloud_query_fixed, + cloud_ref_fixed.get())) { + + PointCloudType::Ptr cloud_ref_local(new PointCloudType()); + mp_cloud_localization->TransformPointsToSensorFrame(*cloud_ref_fixed, + cloud_ref_local.get()); + + // correct relative displacement through scan matching; + PointCloudType::Ptr aligned_query(new PointCloudType()); + mp_cloud_localization->MeasurementUpdateRelocalization(msg_cloud, + cloud_ref_local, aligned_query.get()); + + LOG(INFO) << "... measurement update done!"; + + // [local cloud] -> [global cloud] + mp_cloud_localization->MotionUpdate( + geometry_utils::Transform3::Identity()); + + // input cloud transformed to global frame; + + + mp_cloud_localization->TransformPointsToFixedFrame(*msg_cloud, + mp_cloud_incremental.get()); + } + + // set time stamp associated pose; + geometry_utils::Transform3 pose = + mp_cloud_localization->GetIntegratedEstimate(); + m_pose_latest = TransformStamped(pose, timestamp_now); + mp_cloud_incremental->header.stamp = timestamp_now; + + return false; +} + +void LioLocus::setPosePrior(geometry_utils::Transform3 pose_prior) { + + mp_cloud_localization->SetIntegratedEstimate(pose_prior); +} + +void LioLocus::transformCloudAndInsertToMap(PointCloudType::Ptr msg_cloud) { + + // [local cloud] -> [global cloud] + mp_cloud_localization->MotionUpdate(geometry_utils::Transform3::Identity()); + PointCloudType::Ptr m_cloud_fixed(new PointCloudType()); + mp_cloud_localization->TransformPointsToFixedFrame(*msg_cloud, + m_cloud_fixed.get()); + + // insert cloud to local mapper; + auto current_pose = mp_cloud_localization->GetIntegratedEstimate(); + mp_cloud_mapper->UpdateCurrentPose(current_pose); + + mp_cloud_incremental = PointCloudType::Ptr(new PointCloudType()); + mp_cloud_mapper->InsertPoints(m_cloud_fixed, mp_cloud_incremental.get()); + + // notify size of points inserted to cloud map; + LOG(INFO) << "#[" << m_cloud_fixed->size() + << "] points inserted for cloud map!"; + + return; +} + +PointCloudType::Ptr LioLocus::downsampleCloud(PointCloudType::Ptr input_cloud, + double leaf_size) { + // do filtering on visualization cloud map; + PointCloudType::Ptr cloud_downsampled(new PointCloudType()); + *cloud_downsampled = *input_cloud; + pcl::VoxelGrid voxel_grid_filter; + voxel_grid_filter.setLeafSize(leaf_size, leaf_size, leaf_size); + voxel_grid_filter.setInputCloud(cloud_downsampled); + voxel_grid_filter.filter(*cloud_downsampled); + + // RCLCPP_INFO_STREAM(rclcpp::get_logger(params_lio_locus.log_tag), + // "... during down-sampling cloud -> #[" << input_cloud->size() + // << "] -> #[" << cloud_downsampled->size() << "]"); + + return cloud_downsampled; +} + +bool LioLocus::getCloudMapInMemory(PointCloudType::Ptr ptr_cloud) { + + *ptr_cloud = *mp_cloud_mapper->getCloudMapInMem(); + + if (ptr_cloud == nullptr) + return false; + + // LOG(INFO) << "#[" << ptr_cloud->size() << "] points for cloud map!"; + + return true; +} + +void LioLocus::feedIMUData(IMUData imu_data) { + + if (m_imus.size() >= m_size_imus) { + m_imus.erase(m_imus.begin()); + } + + m_imus.insert(std::make_pair(imu_data.timestamp_, imu_data)); + +} + +Eigen::Matrix3d LioLocus::toRotationMatrix( + geometry_utils::Quaterniond quat_imu) { + + Eigen::Quaterniond q(quat_imu.W(), quat_imu.X(), quat_imu.Y(), + quat_imu.Z()); + Eigen::Matrix3d rot = q.toRotationMatrix(); + + return rot; +} + +// Pose6DOF LioLocus::getCurrentPose6DOF() { + +// auto T = getCurrentPose(); +// auto t_T = T.translation; +// auto q_T = T.rotation; + +// Pose6DOF pose(Eigen::Vector3d(t_T.X(), t_T.Y(), t_T.Z()), +// Eigen::Quaterniond(q_T.Eigen())); + +// return pose; +// } + +// insert the input cloud to mapper; +bool LioLocus::getRelativeRotationFromIMU(double ts, + geometry_utils::Quaterniond &quat_imu) { + +// get IMU message for the given timestamp; + + LOG(INFO) << "... having #[" << m_imus.size() << "] imus!"; + IMUData msg_imu_data; + if (!getMessageAtTimeStamp(ts, msg_imu_data, m_imus)) { + return false; + } + + auto q = msg_imu_data.orientation; + Eigen::Quaterniond quat_cur(q.w(), q.x(), q.y(), q.z()); + + static Eigen::Quaterniond quat_ref = quat_cur; + + Eigen::Quaterniond delta_quat_imu = quat_ref.inverse() * quat_cur; + LOG(INFO) << "... # ROTATION from imu observations -> [" + << Eigen::AngleAxisd(delta_quat_imu).angle() / M_PI * 180 + << "] degree!"; + +// T_cloud2imu * dT_imu * T_imu2cloud = dT_cloud; + Eigen::Quaterniond delta_quat_cloud = m_dq_imu2cloud.inverse() + * delta_quat_imu * m_dq_imu2cloud; + + LOG(INFO) << "... # ROTATION from cloud observations -> [" + << Eigen::AngleAxisd(delta_quat_cloud).angle() / M_PI * 180 + << "] degree!"; + + quat_imu = geometry_utils::Quaterniond(delta_quat_cloud.w(), + delta_quat_cloud.x(), delta_quat_cloud.y(), delta_quat_cloud.z()); + + quat_ref = quat_cur; + return true; +} + +bool LioLocus::getMessageAtTimeStamp(double stamp, IMUData &msg, + map buffer) { + if (buffer.size() == 0) { + return false; + } + auto ts_itr = buffer.lower_bound(stamp); + double time_diff; + + if (ts_itr == buffer.begin()) { + msg = ts_itr->second; + time_diff = ts_itr->first - stamp; + LOG(INFO) << "ts_itr points to buffer begin"; + } else if (ts_itr == buffer.end()) { + ts_itr--; + msg = ts_itr->second; + time_diff = stamp - ts_itr->first; + LOG(INFO) << "ts_itr points to buffer end"; + } else { + double ts_previous = std::prev(ts_itr, 1)->first; + if (ts_itr->first - stamp < stamp - ts_previous) { + msg = ts_itr->second; + time_diff = ts_itr->first - stamp; + } else { + msg = std::prev(ts_itr, 1)->second; + time_diff = stamp - ts_previous; + } + + } // end of search scope; + + LOG(INFO) << "... ts of cloud [" << std::setw(20) + << std::setprecision(20) << stamp << "] v.s. imu [" << std::setw(20) + << std::setprecision(20) << msg.timestamp_ << "] with diff [" + << std::setprecision(20) << "[" << time_diff * 1e3 + << "] milli-sec!"; + + double threshold = 0.3; + if (fabs(time_diff) > threshold) { + + LOG(INFO) << "... #[" << time_diff << "] more than threshold [" + << threshold << "]"; + return false; + } + return true; +} + +} diff --git a/src/localization_module_lio_locus/src/point_cloud_localization/CMakeLists.txt b/src/localization_module_lio_locus/src/point_cloud_localization/CMakeLists.txt new file mode 100755 index 0000000..f59bad8 --- /dev/null +++ b/src/localization_module_lio_locus/src/point_cloud_localization/CMakeLists.txt @@ -0,0 +1,21 @@ +add_library(point_cloud_localization SHARED + PointCloudLocalization.cc utils.cc) + +target_link_libraries(point_cloud_localization + # ${PCL_LIBRARIES} + pcl_octree + pcl_filters + pcl_search + pcl_common + pcl_sample_consensus + ${YAML_CPP_LIBRARIES} + glog +) + +install(TARGETS point_cloud_localization + DESTINATION lib +) + + + + diff --git a/src/localization_module_lio_locus/src/point_cloud_localization/PointCloudLocalization.cc b/src/localization_module_lio_locus/src/point_cloud_localization/PointCloudLocalization.cc new file mode 100755 index 0000000..82ecece --- /dev/null +++ b/src/localization_module_lio_locus/src/point_cloud_localization/PointCloudLocalization.cc @@ -0,0 +1,420 @@ +/* + Authors: + - Matteo Palieri (matteo.palieri@jpl.nasa.gov) + - Benjamin Morrell (benjamin.morrell@jpl.nasa.gov) + - Andrea Tagliabue (andrea.tagliabue@jpl.nasa.gov) + - Andrzej Reinke (andrzej.m.reinke@jpl.nasa.gov) + + - later modified by solomon, + */ + +#include +#include + +namespace gu = geometry_utils; + +using namespace point_cloud_localization; + +PointCloudLocalization::PointCloudLocalization() +{ + + google::SetStderrLogging(google::GLOG_INFO); + FLAGS_colorlogtostderr = true; + FLAGS_alsologtostderr = true; +} + +PointCloudLocalization::~PointCloudLocalization() +{ + +} + +bool PointCloudLocalization::Initialize(std::string path_to_params) +{ + + if (!loadParametersFromFile(path_to_params)) + return false; + + applyParameters(); + + if (!SetupICP()) + { + LOG(ERROR) << "Failed to SetupICP"; + } + + return true; +} + +bool PointCloudLocalization::loadParametersFromFile(std::string path_to_file) +{ + + if (!boost::filesystem::exists(path_to_file)) + { + LOG(ERROR) << "file NOT exists for parameter loading -> [" << path_to_file << "]"; + + return false; + } + else + { + + LOG(INFO) << "... reading parameter for localization from [" << path_to_file << "]!"; + } + + YAML::Node yaml_node = YAML::LoadFile(path_to_file); + b_is_flat_ground_assumption_ = yaml_node["b_is_flat_ground_assumption"].as(); + auto node_loc = yaml_node["localization"]; + + // for cloud registration; + params_.registration_method = + node_loc["registration_method"].as(); + params_.iterations = node_loc["iterations"].as(); + params_.num_threads = node_loc["num_threads"].as(); + params_.k_nearest_neighbours_ = node_loc["normal_search_radius"].as(); + + params_.tf_epsilon = node_loc["tf_epsilon"].as(); + params_.corr_dist = node_loc["corr_dist"].as(); + + // for cloud registration result evaluation critera; + transform_thresholding_ = node_loc["transform_thresholding"].as(); + max_translation_ = node_loc["max_translation"].as(); + max_rotation_ = node_loc["max_rotation"].as(); + + recompute_covariance_local_map_ = + node_loc["recompute_covariance_local_map"].as(); + recompute_covariance_scan_ = + node_loc["recompute_covariance_scan"].as(); + + return true; +} + +void PointCloudLocalization::applyParameters() +{ + + double init_x = 0.0, init_y = 0.0, init_z = 0.0; + double init_qx = 0.0, init_qy = 0.0, init_qz = 0.0, init_qw = 1.0; + bool b_have_fiducial = true; + + double init_roll = 0.0, init_pitch = 0.0, init_yaw = 0.0; + gu::Quat q(gu::Quat(init_qw, init_qx, init_qy, init_qz)); + gu::Rot3 R; + R = gu::QuatToR(q); + + init_roll = R.Roll(); + init_pitch = R.Pitch(); + init_yaw = R.Yaw(); + + integrated_estimate_.translation = gu::Vec3(init_x, init_y, init_z); + integrated_estimate_.rotation = gu::Rot3(init_roll, init_pitch, init_yaw); + + if (b_is_flat_ground_assumption_) + { + integrated_estimate_.rotation = gu::Rot3(0, 0, + integrated_estimate_.rotation.Yaw()); + } + + if (!b_have_fiducial) + { + LOG(WARNING) << + "Can't find fiducials, using origin"; + } + else + { + LOG(INFO) << "Using:\nTranslation:\n" + << integrated_estimate_.translation << "\nRotation\n" + << integrated_estimate_.rotation.Roll() * 180.0 / M_PI << ", " + << integrated_estimate_.rotation.Pitch() * 180.0 / M_PI << ", " << integrated_estimate_.rotation.Yaw() * 180.0 / M_PI; + } +} + +const gu::Transform3 &PointCloudLocalization::GetIncrementalEstimate() const +{ + return incremental_estimate_; +} + +const gu::Transform3 &PointCloudLocalization::GetIntegratedEstimate() const +{ + return integrated_estimate_; +} + +void PointCloudLocalization::SetIntegratedEstimate( + const gu::Transform3 &integrated_estimate) +{ + integrated_estimate_ = integrated_estimate; +} + +bool PointCloudLocalization::MotionUpdate( + const gu::Transform3 &incremental_odom) +{ + // Store the incremental transform from odometry + incremental_estimate_ = incremental_odom; + return true; +} + +// cloud points transformation vice versa; +bool PointCloudLocalization::TransformPointsToFixedFrame( + const PointCloudF &points, PointCloudF *points_transformed) const +{ + if (points_transformed == NULL) + { + + return false; + } + + // [world] => [robot]; + const gu::Transform3 estimate = gu::PoseUpdate(integrated_estimate_, + incremental_estimate_); + + Eigen::Matrix4d tf; + tf.block(0, 0, 3, 3) = estimate.rotation.Eigen(); + tf.block(0, 3, 3, 1) = estimate.translation.Eigen(); + + pcl::transformPointCloudWithNormals(points, *points_transformed, tf); + + return true; +} + +bool PointCloudLocalization::TransformPointsToSensorFrame( + const PointCloudF &points, PointCloudF *points_transformed) const +{ + if (points_transformed == NULL) + { + return false; + } + + // [robot] <= [world] + const gu::Transform3 estimate = gu::PoseInverse( + gu::PoseUpdate(integrated_estimate_, incremental_estimate_)); + + Eigen::Matrix4d tf; + tf.block(0, 0, 3, 3) = estimate.rotation.Eigen(); + tf.block(0, 3, 3, 1) = estimate.translation.Eigen(); + + pcl::transformPointCloudWithNormals(points, *points_transformed, tf); + + return true; +} + +bool PointCloudLocalization::SetupICP() +{ + + LOG(INFO) << "####################################################"; + LOG(INFO) << " PointCloudLocalization - SetupICP "; + LOG(INFO) << "####################################################"; + + RegistrationMethod method; + + if (params_.registration_method == "gicp") + method = RegistrationMethod::GICP; + else if (params_.registration_method == "ndt") + method = RegistrationMethod::NDT; + + switch (method) + { + case RegistrationMethod::GICP: + { + LOG(INFO) << + "RegistrationMethod::GICP activated."; + pcl::MultithreadedGeneralizedIterativeClosestPoint::Ptr gicp = + boost::make_shared< + pcl::MultithreadedGeneralizedIterativeClosestPoint< + PointF, PointF>>(); + + gicp->setTransformationEpsilon(params_.tf_epsilon); + gicp->setMaxCorrespondenceDistance(params_.corr_dist); + gicp->setMaximumIterations(params_.iterations); + gicp->setRANSACIterations(0); + gicp->setMaximumOptimizerIterations(50); + gicp->setNumThreads(params_.num_threads); + gicp->enableTimingOutput(params_.enable_timing_output); + gicp->RecomputeTargetCovariance(recompute_covariance_local_map_); + gicp->RecomputeSourceCovariance(recompute_covariance_scan_); // local scan we don't need to + // recompute + gicp->setEuclideanFitnessEpsilon(0.01); + LOG(INFO) << "GICP activated."; + + LOG(INFO) << "num threads: " << params_.num_threads; + + LOG(INFO) << "MaxCorrespondenceDistance: " << gicp->getMaxCorrespondenceDistance(); + + LOG(INFO) << "MaximumIterations: " << gicp->getMaximumIterations(); + LOG(INFO) << "TransformationEpsilon: " << gicp->getTransformationEpsilon(); + LOG(INFO) << "EuclideanFitnessEpsilon: " << gicp->getEuclideanFitnessEpsilon(); + LOG(INFO) << "RANSACIterations: " << gicp->getRANSACIterations(); + + LOG(INFO) << "RotationEpsilon " << gicp->getRotationEpsilon(); + LOG(INFO) << "CorrespondenceRandomness:" << gicp->getCorrespondenceRandomness(); + LOG(INFO) << "MaximumOptimizerIterations:" << gicp->getMaximumOptimizerIterations(); + LOG(INFO) << "ConvergeCriteria:" << gicp->getConvergeCriteria(); + LOG(INFO) << "RANSACOutlierRejectionThreshold: " << gicp->getRANSACOutlierRejectionThreshold(); + icp_ = gicp; + + break; + } + case RegistrationMethod::NDT: + { + LOG(INFO) << "RegistrationMethod::NDT activated."; + pclomp::NormalDistributionsTransform::Ptr ndt_omp = + boost::make_shared< + pclomp::NormalDistributionsTransform>(); + + ndt_omp->setTransformationEpsilon(params_.tf_epsilon); + ndt_omp->setMaxCorrespondenceDistance(params_.corr_dist); + ndt_omp->setMaximumIterations(params_.iterations); + ndt_omp->setRANSACIterations(0); + ndt_omp->setNumThreads(params_.num_threads); + ndt_omp->enableTimingOutput(params_.enable_timing_output); + icp_ = ndt_omp; + break; + } + default: + throw std::runtime_error( + "No such Registration mode or not implemented yet " + params_.registration_method); + } + + return true; +} + +// two clouds only deviates for a small range, otherwise, use motion prior; +bool PointCloudLocalization::MeasurementUpdate(const PointCloudF::Ptr &query, + const PointCloudF::Ptr &reference, PointCloudF *aligned_query) +{ + + // 1. transformation estimation; + if (aligned_query == NULL) + { + LOG(WARNING) << "... aligned query NULL for [MeasurementUpdate]"; + return false; + } + + timestamp_ = query->header.stamp * 1e3; + icp_->setInputSource(query); + icp_->setInputTarget(reference); + PointCloudF icpAlignedPointsLocalization_; + icp_->align(icpAlignedPointsLocalization_); + + const Eigen::Matrix4f T = icp_->getFinalTransformation(); + //------------------------------------------------------------------------- + // 2. transformation modification if needed; + + // rotation from eigen isometry to udf; + geometry_utils::Rot3 rot_gu = gu::Rot3(T(0, 0), T(0, 1), T(0, 2), T(1, 0), + T(1, 1), T(1, 2), T(2, 0), T(2, 1), T(2, 2)); + + gu::Transform3 pose_update; + if (b_is_flat_ground_assumption_) + { + + // get euler angle from rotation matrix; + double roll, pitch, yaw; + + roll = rot_gu.Roll(); + pitch = rot_gu.Pitch(); + yaw = rot_gu.Yaw(); + + pose_update.translation = gu::Vec3(T(0, 3), T(1, 3), 0); + pose_update.rotation = gu::Rot3(cos(yaw), -sin(yaw), 0, sin(yaw), + cos(yaw), 0, 0, 0, 1); + + LOG(INFO) << "... using flat ground assumption!"; + } + else + { + pose_update.translation = gu::Vec3(T(0, 3), T(1, 3), T(2, 3)); + pose_update.rotation = rot_gu; + } + //------------------------------------------------------------------------- + // 3. transformation evaluation and assignment to incremental update; + if (!transform_thresholding_ || (pose_update.translation.Norm() <= max_translation_ && pose_update.rotation.ToEulerZYX().Norm() <= max_rotation_)) + { + + incremental_estimate_ = gu::PoseUpdate(incremental_estimate_, + pose_update); + } + else + { + LOG(WARNING) << + "Discarding incremental transformation with norm (t: %lf, r: %lf)", + pose_update.translation.Norm(), + pose_update.rotation.ToEulerZYX().Norm(); + } + + //------------------------------------------------------------------------- + // 4. integrated pose update; + integrated_estimate_ = gu::PoseUpdate(integrated_estimate_, + incremental_estimate_); + //====================================================================================== + // get data association correspondences for the transformation; + score_registration_ = icp_->getFitnessScore(1.0); + + return true; +} + +bool PointCloudLocalization::MeasurementUpdateRelocalization( + const PointCloudF::Ptr &query, const PointCloudF::Ptr &reference, + PointCloudF *aligned_query) +{ + + if (aligned_query == NULL) + { + LOG(WARNING) << "... aligned query NULL for [MeasurementUpdateRelocalization]"; + return false; + } + + // Store time stamp + timestamp_ = query->header.stamp * 1e3; + + // cloud registration from query to reference; + icp_->setInputSource(query); + icp_->setInputTarget(reference); + + // query -> transformed, v.s. ref.; + PointCloudF icpAlignedPointsLocalization_; + icp_->align(icpAlignedPointsLocalization_); + + // Retrieve transformation and estimate and update + const Eigen::Matrix4f T = icp_->getFinalTransformation(); + //--------------------------------------------------------- + geometry_utils::Rot3 rot_gu = gu::Rot3(T(0, 0), T(0, 1), T(0, 2), T(1, 0), + T(1, 1), T(1, 2), T(2, 0), T(2, 1), T(2, 2)); + + gu::Transform3 pose_update; + if (b_is_flat_ground_assumption_) + { + // get euler angle from rotation matrix; + double roll, pitch, yaw; + //----------------------------------------------------------------------------------- + roll = rot_gu.Roll(); + pitch = rot_gu.Pitch(); + yaw = rot_gu.Yaw(); + + pose_update.translation = gu::Vec3(T(0, 3), T(1, 3), 0); + pose_update.rotation = gu::Rot3(cos(yaw), -sin(yaw), 0, sin(yaw), + cos(yaw), 0, 0, 0, 1); + } + else + { + pose_update.translation = gu::Vec3(T(0, 3), T(1, 3), T(2, 3)); + pose_update.rotation = rot_gu; + } + //--------------------------------------------------------- + // for global positioning, can update pose without incremental motion constraint; + incremental_estimate_ = gu::PoseUpdate(incremental_estimate_, pose_update); + //--------------------------------------------------------- + // current time pose prior is concatenated with history record; + integrated_estimate_ = gu::PoseUpdate(integrated_estimate_, + incremental_estimate_); + + //===================================================================================== + score_registration_ = icp_->getFitnessScore(1.0); + LOG(INFO) << "... during re-localization measurement update: score -> #[" << score_registration_ << "]"; + + return true; +} // end of scope for reloc measurement update; + +void PointCloudLocalization::SetFlatGroundAssumptionValue(const bool &value) +{ + LOG(INFO) << "PointCloudLocalization - SetFlatGroundAssumptionValue - Received: " << value; + b_is_flat_ground_assumption_ = value; + if (value) + integrated_estimate_.rotation = gu::Rot3(0, 0, + integrated_estimate_.rotation.Yaw()); +} diff --git a/src/localization_module_lio_locus/src/point_cloud_localization/utils.cc b/src/localization_module_lio_locus/src/point_cloud_localization/utils.cc new file mode 100755 index 0000000..1f6bcf5 --- /dev/null +++ b/src/localization_module_lio_locus/src/point_cloud_localization/utils.cc @@ -0,0 +1,163 @@ +#include + +void addNormal(const PointCloudF &cloud, + pcl::PointCloud::Ptr &cloud_with_normals, + const int k_nearest_neighbours) { + pcl::PointCloud::Ptr normals(new pcl::PointCloud); + cloud_with_normals.reset(new pcl::PointCloud); + pcl::PointCloud::Ptr cloud_xyz( + new pcl::PointCloud); + // Convert point cloud XYZI to XYZ + + for (size_t i = 0; i < cloud.size(); i++) { + pcl::PointXYZ point; + point.x = cloud.points[i].x; + point.y = cloud.points[i].y; + point.z = cloud.points[i].z; + cloud_xyz->points.push_back(point); + } + + pcl::search::KdTree::Ptr searchTree( + new pcl::search::KdTree); + searchTree->setInputCloud(cloud_xyz); + + pcl::NormalEstimationOMP normalEstimator(4); // parallel + // TODO: if it's commented out => we don't use it => time to remove ? + // pcl::NormalEstimation normalEstimator; + // not + // parallel + + normalEstimator.setInputCloud(cloud_xyz); + normalEstimator.setSearchMethod(searchTree); + normalEstimator.setKSearch(k_nearest_neighbours); + normalEstimator.compute(*normals); + + pcl::concatenateFields(*cloud_xyz, *normals, *cloud_with_normals); +} + +void addNormal(const PointCloudF &cloud, PointCloudF::Ptr &cloud_with_normals, + const int k_nearest_neighbours) { + pcl::PointCloud::Ptr normals(new pcl::PointCloud); + pcl::PointCloud::Ptr cloud_xyz( + new pcl::PointCloud); + // Convert point cloud XYZI to XYZ + + for (size_t i = 0; i < cloud.size(); i++) { + pcl::PointXYZ point; + point.x = cloud.points[i].x; + point.y = cloud.points[i].y; + point.z = cloud.points[i].z; + cloud_xyz->points.push_back(point); + } + + pcl::search::KdTree::Ptr searchTree( + new pcl::search::KdTree); + searchTree->setInputCloud(cloud_xyz); + + pcl::NormalEstimationOMP normalEstimator(4); // parallel + // TODO: if it's commented out => we don't use it => time to remove ? + // pcl::NormalEstimation normalEstimator; + // not + // parallel + + normalEstimator.setInputCloud(cloud_xyz); + normalEstimator.setSearchMethod(searchTree); + normalEstimator.setKSearch(k_nearest_neighbours); + normalEstimator.compute(*normals); + + for (size_t i = 0; i < cloud.size(); i++) { + pcl::PointXYZ point; + cloud_with_normals->points[i].normal_x = normals->points[i].normal_x; + cloud_with_normals->points[i].normal_y = normals->points[i].normal_y; + cloud_with_normals->points[i].normal_z = normals->points[i].normal_z; + } +} + +// returns a point cloud whose centroid is the origin, and that the mean of +// the distances to the origin is 1 + +// get the mean of the cloud; + +void normalizePCloud(const pcl::PointCloud &cloud, + pcl::PointCloud::Ptr pclptr_normalized) { + + // 1. centroid of the cloud; + Eigen::Vector4f centroid_4d; + pcl::compute3DCentroid(cloud, centroid_4d); + Eigen::Vector3f centroid(centroid_4d.x(), centroid_4d.y(), centroid_4d.z()); + + // 2. add up all distance of point to centroid; + float dist = 0; + for (pcl::PointCloud::const_iterator it = + cloud.points.begin(); it != cloud.points.end(); it++) { + Eigen::Vector3f a_i(it->x, it->y, it->z); + dist = dist + (a_i - centroid).norm(); + } + float factor = cloud.points.size() / dist; + Eigen::Matrix4f transform; + transform = Eigen::Matrix4f::Identity(); + + // centroid *1/(summation of distance/N) + + // factor = 1.0/(sum of distance / N ) + // factor = 1.0 / mean distance; + transform.block(0, 0, 3, 3) = factor * Eigen::Matrix3f::Identity(); + transform.block(0, 3, 4, 1) = -factor * centroid_4d; + + // [R,t] * p = (R*p + t) * factor; + // [I, -centroid] * p = (p - centroid)* factor; + // (P- centroid)/mean distance to centroid; + pcl::transformPointCloud(cloud, *pclptr_normalized, transform); + pcl::compute3DCentroid(*pclptr_normalized, centroid_4d); + + // checkIfPCloudIsNormalized(pclptr_normalized); // +} + +void normalizePCloud(const PointCloudF &cloud, + PointCloudF::Ptr pclptr_normalized) { + Eigen::Vector4f centroid_4d; + pcl::compute3DCentroid(cloud, centroid_4d); + Eigen::Vector3f centroid(centroid_4d.x(), centroid_4d.y(), centroid_4d.z()); + + float dist = 0; + for (PointCloudF::const_iterator it = cloud.points.begin(); + it != cloud.points.end(); it++) { + Eigen::Vector3f a_i(it->x, it->y, it->z); + dist = dist + (a_i - centroid).norm(); + } + float factor = cloud.points.size() / dist; + Eigen::Matrix4f transform; + transform = Eigen::Matrix4f::Identity(); + transform.block(0, 0, 3, 3) = factor * Eigen::Matrix3f::Identity(); + transform.block(0, 3, 4, 1) = -factor * centroid_4d; + pcl::transformPointCloud(cloud, *pclptr_normalized, transform); + pcl::compute3DCentroid(*pclptr_normalized, centroid_4d); + + // checkIfPCloudIsNormalized(pclptr_normalized); // +} + +void doEigenDecomp6x6(const Eigen::Matrix &data, + Eigen::Matrix &eigenvalues, + Eigen::Matrix &eigenvectors) { + Eigen::SelfAdjointEigenSolver> eigensolver( + data); + if (eigensolver.info() == Eigen::Success) { + eigenvalues = eigensolver.eigenvalues(); + eigenvectors = eigensolver.eigenvectors(); // the eigenvectors are the columns + } else { + std::cout << "Eigen failed to do the eigendecomp" << std::endl; + } +} + +void doEigenDecomp3x3(const Eigen::Matrix &data, + Eigen::Matrix &eigenvalues, + Eigen::Matrix &eigenvectors) { + Eigen::SelfAdjointEigenSolver> eigensolver( + data); + if (eigensolver.info() == Eigen::Success) { + eigenvalues = eigensolver.eigenvalues(); + eigenvectors = eigensolver.eigenvectors(); // the eigenvectors are the columns + } else { + std::cout << "Eigen failed to do the eigendecomp" << std::endl; + } +} diff --git a/src/localization_module_lio_locus/src/point_cloud_mapper/CMakeLists.txt b/src/localization_module_lio_locus/src/point_cloud_mapper/CMakeLists.txt new file mode 100755 index 0000000..f974885 --- /dev/null +++ b/src/localization_module_lio_locus/src/point_cloud_mapper/CMakeLists.txt @@ -0,0 +1,27 @@ + +add_library(point_cloud_mapper SHARED + PointCloudIkdTreeMapper.cc + ikd_tree/ikd_Tree.cpp +) + + +target_include_directories(point_cloud_mapper PUBLIC + # ${PCL_INCLUDE_DIRS} + /home/demo/deps_install/include/pcl-1.10 + ) + +target_link_libraries(point_cloud_mapper + ${PCL_LIBRARIRES} + ${YAML_CPP_LIBRARIES} + glog + OpenMP::OpenMP_CXX +) + + +install(TARGETS point_cloud_mapper + DESTINATION lib +# DESTINATION lib/${PROJECT_NAME} +) + + + diff --git a/src/localization_module_lio_locus/src/point_cloud_mapper/PointCloudIkdTreeMapper.cc b/src/localization_module_lio_locus/src/point_cloud_mapper/PointCloudIkdTreeMapper.cc new file mode 100755 index 0000000..283e9e2 --- /dev/null +++ b/src/localization_module_lio_locus/src/point_cloud_mapper/PointCloudIkdTreeMapper.cc @@ -0,0 +1,148 @@ +#include +#include +#include +#include + +#include +#include +//#include + +PointCloudIkdTreeMapper::PointCloudIkdTreeMapper() : + initialized_(false) { + + map_data_.reset(new PointCloudF); + + google::SetStderrLogging(google::GLOG_INFO); + FLAGS_colorlogtostderr = true; + FLAGS_alsologtostderr = true; +} + +PointCloudIkdTreeMapper::~PointCloudIkdTreeMapper() { +} + +bool PointCloudIkdTreeMapper::Initialize(std::string path_to_params) { + + if (!loadParametersFromFile(path_to_params)) + return false; + ikdtree.set_downsample_param(octree_resolution_); + + // mp_cloud_mapper->SetupNumberThreads(6); + + + initialized_ = true; + return true; +} + +bool PointCloudIkdTreeMapper::loadParametersFromFile(std::string path_to_file) { + + if (!boost::filesystem::exists(path_to_file)) { + LOG(INFO) << "file NOT exists for parameter loading!\n"; + return false; + } else { + LOG(INFO) << + "... reading parameter for mapper from [" << path_to_file << "]!"; + + } + + YAML::Node yaml_node = YAML::LoadFile(path_to_file); + octree_resolution_ = yaml_node["map"]["octree_resolution"].as(); + fixed_frame_id_ = yaml_node["map"]["frame_id_fixed"].as(); + num_threads_ = yaml_node["map"]["num_threads"].as(); + + SetupNumberThreads(num_threads_); + + LOG(INFO) << "# octree_resolution -> [" << octree_resolution_ << "]"; + LOG(INFO) << "# fixed_frame_id -> [" << fixed_frame_id_ << "]"; + + return true; +} + +void PointCloudIkdTreeMapper::Reset() { + + map_data_.reset(new PointCloudF); + + initialized_ = true; +} + +bool PointCloudIkdTreeMapper::InsertPoints(const PointCloudF::ConstPtr &points, + PointCloudF *incremental_points) { + if (!initialized_) { + return false; + } + + if (incremental_points == NULL) { + incremental_points = new PointCloudF(); + } + incremental_points->clear(); + + if (map_mutex_.try_lock()) { + if (ikdtree.size() == 0) { + + ikdtree.Build(*points); + } else { + PointVector pc_append(*points); + ikdtree.Add_Points(pc_append, false); + } + map_mutex_.unlock(); + } else { + // This won't happen often. + LOG(WARNING) << + "... insertion points to cloud map failed for iKD-tree!"; + } + + *incremental_points = *points; + + // Publish the incremental map update. + incremental_points->header = points->header; + incremental_points->header.frame_id = fixed_frame_id_; + + return true; +} + +bool PointCloudIkdTreeMapper::ApproxNearestNeighbors(const PointCloudF &points, + PointCloudF *neighbors) { + if (!initialized_) { + + LOG(WARNING) <<"... not init yet for point cloud iKD-tree!"; + return false; + } + + if (neighbors == NULL) { + neighbors = new PointCloudF(); + } + + neighbors->points.clear(); + neighbors->resize(points.points.size()); + PointVector search_result; + + omp_set_num_threads (number_threads_); +#pragma omp parallel for schedule(dynamic, 1) + for (size_t ii = 0; ii < points.points.size(); ++ii) { + PointVector search_result; + vector PointDist; + ikdtree.Nearest_Search(points[ii], 1, search_result, PointDist); + + neighbors->points[ii] = search_result[0]; + } + + return neighbors->points.size() > 0; +} + +PointCloudF::Ptr PointCloudIkdTreeMapper::getCloudMapInMem() { + + PointCloudF::Ptr cloud_map(new PointCloudF()); + + map_mutex_.lock(); + PointVector storage; + storage.header.frame_id = fixed_frame_id_; + ikdtree.flatten(ikdtree.Root_Node, storage, NOT_RECORD); + map_mutex_.unlock(); + + *cloud_map = storage; + + return cloud_map; + +} + +void PointCloudIkdTreeMapper::SetBoxFilterSize(const int box_filter_size) { +} diff --git a/src/localization_module_lio_locus/src/point_cloud_mapper/ikd_tree/ikd_Tree.cpp b/src/localization_module_lio_locus/src/point_cloud_mapper/ikd_tree/ikd_Tree.cpp new file mode 100755 index 0000000..8903c1e --- /dev/null +++ b/src/localization_module_lio_locus/src/point_cloud_mapper/ikd_tree/ikd_Tree.cpp @@ -0,0 +1,1663 @@ +#include "ikd_tree/ikd_Tree.h" + +/* +Description: ikd-Tree: an incremental k-d tree for robotic applications +Author: Yixi Cai +email: yixicai@connect.hku.hk +*/ + +KD_TREE::KD_TREE(float delete_param, float balance_param, float box_length) { + delete_criterion_param = delete_param; + balance_criterion_param = balance_param; + downsample_size = box_length; + Rebuild_Logger.clear(); + termination_flag = false; + start_thread(); +} + +KD_TREE::~KD_TREE() { + stop_thread(); + Delete_Storage_Disabled = true; + delete_tree_nodes(&Root_Node); + PointVector().swap(PCL_Storage); + Rebuild_Logger.clear(); +} + +void KD_TREE::Set_delete_criterion_param(float delete_param) { + delete_criterion_param = delete_param; +} + +void KD_TREE::Set_balance_criterion_param(float balance_param) { + balance_criterion_param = balance_param; +} + +void KD_TREE::set_downsample_param(float downsample_param) { + downsample_size = downsample_param; +} + +void KD_TREE::InitializeKDTree(float delete_param, + float balance_param, + float box_length) { + Set_delete_criterion_param(delete_param); + Set_balance_criterion_param(balance_param); + set_downsample_param(box_length); +} + +void KD_TREE::InitTreeNode(KD_TREE_NODE* root) { + root->point.x = 0.0f; + root->point.y = 0.0f; + root->point.z = 0.0f; + root->node_range_x[0] = 0.0f; + root->node_range_x[1] = 0.0f; + root->node_range_y[0] = 0.0f; + root->node_range_y[1] = 0.0f; + root->node_range_z[0] = 0.0f; + root->node_range_z[1] = 0.0f; + root->division_axis = 0; + root->father_ptr = nullptr; + root->left_son_ptr = nullptr; + root->right_son_ptr = nullptr; + root->TreeSize = 0; + root->invalid_point_num = 0; + root->down_del_num = 0; + root->point_deleted = false; + root->tree_deleted = false; + root->need_push_down_to_left = false; + root->need_push_down_to_right = false; + root->point_downsample_deleted = false; + root->working_flag = false; + pthread_mutex_init(&(root->push_down_mutex_lock), NULL); +} + +int KD_TREE::size() { + int s = 0; + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node) { + if (Root_Node != nullptr) { + return Root_Node->TreeSize; + } else { + return 0; + } + } else { + if (!pthread_mutex_trylock(&working_flag_mutex)) { + s = Root_Node->TreeSize; + pthread_mutex_unlock(&working_flag_mutex); + return s; + } else { + return Treesize_tmp; + } + } +} + +BoxPointType KD_TREE::tree_range() { + BoxPointType range; + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node) { + if (Root_Node != nullptr) { + range.vertex_min[0] = Root_Node->node_range_x[0]; + range.vertex_min[1] = Root_Node->node_range_y[0]; + range.vertex_min[2] = Root_Node->node_range_z[0]; + range.vertex_max[0] = Root_Node->node_range_x[1]; + range.vertex_max[1] = Root_Node->node_range_y[1]; + range.vertex_max[2] = Root_Node->node_range_z[1]; + } else { + memset(&range, 0, sizeof(range)); + } + } else { + if (!pthread_mutex_trylock(&working_flag_mutex)) { + range.vertex_min[0] = Root_Node->node_range_x[0]; + range.vertex_min[1] = Root_Node->node_range_y[0]; + range.vertex_min[2] = Root_Node->node_range_z[0]; + range.vertex_max[0] = Root_Node->node_range_x[1]; + range.vertex_max[1] = Root_Node->node_range_y[1]; + range.vertex_max[2] = Root_Node->node_range_z[1]; + pthread_mutex_unlock(&working_flag_mutex); + } else { + memset(&range, 0, sizeof(range)); + } + } + return range; +} + +int KD_TREE::validnum() { + int s = 0; + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node) { + if (Root_Node != nullptr) + return (Root_Node->TreeSize - Root_Node->invalid_point_num); + else + return 0; + } else { + if (!pthread_mutex_trylock(&working_flag_mutex)) { + s = Root_Node->TreeSize - Root_Node->invalid_point_num; + pthread_mutex_unlock(&working_flag_mutex); + return s; + } else { + return -1; + } + } +} + +void KD_TREE::root_alpha(float& alpha_bal, float& alpha_del) { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node) { + alpha_bal = Root_Node->alpha_bal; + alpha_del = Root_Node->alpha_del; + return; + } else { + if (!pthread_mutex_trylock(&working_flag_mutex)) { + alpha_bal = Root_Node->alpha_bal; + alpha_del = Root_Node->alpha_del; + pthread_mutex_unlock(&working_flag_mutex); + return; + } else { + alpha_bal = alpha_bal_tmp; + alpha_del = alpha_del_tmp; + return; + } + } +} + +void KD_TREE::start_thread() { + pthread_mutex_init(&termination_flag_mutex_lock, NULL); + pthread_mutex_init(&rebuild_ptr_mutex_lock, NULL); + pthread_mutex_init(&rebuild_logger_mutex_lock, NULL); + pthread_mutex_init(&points_deleted_rebuild_mutex_lock, NULL); + pthread_mutex_init(&working_flag_mutex, NULL); + pthread_mutex_init(&search_flag_mutex, NULL); + pthread_create(&rebuild_thread, NULL, multi_thread_ptr, (void*)this); + printf("Multi thread started \n"); +} + +void KD_TREE::stop_thread() { + pthread_mutex_lock(&termination_flag_mutex_lock); + termination_flag = true; + pthread_mutex_unlock(&termination_flag_mutex_lock); + if (rebuild_thread) + pthread_join(rebuild_thread, NULL); + pthread_mutex_destroy(&termination_flag_mutex_lock); + pthread_mutex_destroy(&rebuild_logger_mutex_lock); + pthread_mutex_destroy(&rebuild_ptr_mutex_lock); + pthread_mutex_destroy(&points_deleted_rebuild_mutex_lock); + pthread_mutex_destroy(&working_flag_mutex); + pthread_mutex_destroy(&search_flag_mutex); +} + +void* KD_TREE::multi_thread_ptr(void* arg) { + KD_TREE* handle = (KD_TREE*)arg; + handle->multi_thread_rebuild(); + return nullptr; +} + +void KD_TREE::multi_thread_rebuild() { + bool terminated = false; + KD_TREE_NODE *father_ptr, **new_node_ptr; + pthread_mutex_lock(&termination_flag_mutex_lock); + terminated = termination_flag; + pthread_mutex_unlock(&termination_flag_mutex_lock); + while (!terminated) { + pthread_mutex_lock(&rebuild_ptr_mutex_lock); + pthread_mutex_lock(&working_flag_mutex); + if (Rebuild_Ptr != nullptr) { + /* Traverse and copy */ + if (!Rebuild_Logger.empty()) { + printf("\n\n\n\n\n\n\n\n\n\n\n ERROR!!! \n\n\n\n\n\n\n\n\n"); + } + rebuild_flag = true; + if (*Rebuild_Ptr == Root_Node) { + Treesize_tmp = Root_Node->TreeSize; + Validnum_tmp = Root_Node->TreeSize - Root_Node->invalid_point_num; + alpha_bal_tmp = Root_Node->alpha_bal; + alpha_del_tmp = Root_Node->alpha_del; + } + KD_TREE_NODE* old_root_node = (*Rebuild_Ptr); + father_ptr = (*Rebuild_Ptr)->father_ptr; + PointVector().swap(Rebuild_PCL_Storage); + // Lock Search + pthread_mutex_lock(&search_flag_mutex); + while (search_mutex_counter != 0) { + pthread_mutex_unlock(&search_flag_mutex); + usleep(1); + pthread_mutex_lock(&search_flag_mutex); + } + search_mutex_counter = -1; + pthread_mutex_unlock(&search_flag_mutex); + // Lock deleted points cache + pthread_mutex_lock(&points_deleted_rebuild_mutex_lock); + flatten(*Rebuild_Ptr, Rebuild_PCL_Storage, MULTI_THREAD_REC); + // Unlock deleted points cache + pthread_mutex_unlock(&points_deleted_rebuild_mutex_lock); + // Unlock Search + pthread_mutex_lock(&search_flag_mutex); + search_mutex_counter = 0; + pthread_mutex_unlock(&search_flag_mutex); + pthread_mutex_unlock(&working_flag_mutex); + /* Rebuild and update missed operations*/ + Operation_Logger_Type Operation; + KD_TREE_NODE* new_root_node = nullptr; + if (int(Rebuild_PCL_Storage.size()) > 0) { + BuildTree(&new_root_node, + 0, + Rebuild_PCL_Storage.size() - 1, + Rebuild_PCL_Storage); + // Rebuild has been done. Updates the blocked operations into the new + // tree + pthread_mutex_lock(&working_flag_mutex); + pthread_mutex_lock(&rebuild_logger_mutex_lock); + int tmp_counter = 0; + while (!Rebuild_Logger.empty()) { + Operation = Rebuild_Logger.front(); + max_queue_size = max(max_queue_size, Rebuild_Logger.size()); + Rebuild_Logger.pop(); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + pthread_mutex_unlock(&working_flag_mutex); + run_operation(&new_root_node, Operation); + tmp_counter++; + if (tmp_counter % 10 == 0) + usleep(1); + pthread_mutex_lock(&working_flag_mutex); + pthread_mutex_lock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + /* Replace to original tree*/ + // pthread_mutex_lock(&working_flag_mutex); + pthread_mutex_lock(&search_flag_mutex); + while (search_mutex_counter != 0) { + pthread_mutex_unlock(&search_flag_mutex); + usleep(1); + pthread_mutex_lock(&search_flag_mutex); + } + search_mutex_counter = -1; + pthread_mutex_unlock(&search_flag_mutex); + if (father_ptr->left_son_ptr == *Rebuild_Ptr) { + father_ptr->left_son_ptr = new_root_node; + } else if (father_ptr->right_son_ptr == *Rebuild_Ptr) { + father_ptr->right_son_ptr = new_root_node; + } else { + throw "Error: Father ptr incompatible with current node\n"; + } + if (new_root_node != nullptr) + new_root_node->father_ptr = father_ptr; + (*Rebuild_Ptr) = new_root_node; + int valid_old = + old_root_node->TreeSize - old_root_node->invalid_point_num; + int valid_new = + new_root_node->TreeSize - new_root_node->invalid_point_num; + if (father_ptr == STATIC_ROOT_NODE) + Root_Node = STATIC_ROOT_NODE->left_son_ptr; + KD_TREE_NODE* update_root = *Rebuild_Ptr; + while (update_root != nullptr && update_root != Root_Node) { + update_root = update_root->father_ptr; + if (update_root->working_flag) + break; + if (update_root == update_root->father_ptr->left_son_ptr && + update_root->father_ptr->need_push_down_to_left) + break; + if (update_root == update_root->father_ptr->right_son_ptr && + update_root->father_ptr->need_push_down_to_right) + break; + Update(update_root); + } + pthread_mutex_lock(&search_flag_mutex); + search_mutex_counter = 0; + pthread_mutex_unlock(&search_flag_mutex); + Rebuild_Ptr = nullptr; + pthread_mutex_unlock(&working_flag_mutex); + rebuild_flag = false; + /* Delete discarded tree nodes */ + delete_tree_nodes(&old_root_node); + } else { + pthread_mutex_unlock(&working_flag_mutex); + } + pthread_mutex_unlock(&rebuild_ptr_mutex_lock); + pthread_mutex_lock(&termination_flag_mutex_lock); + terminated = termination_flag; + pthread_mutex_unlock(&termination_flag_mutex_lock); + usleep(100); + } + printf("Rebuild thread terminated normally\n"); +} + +void KD_TREE::run_operation(KD_TREE_NODE** root, + Operation_Logger_Type operation) { + switch (operation.op) { + case ADD_POINT: + Add_by_point(root, operation.point, false, (*root)->division_axis); + break; + case ADD_BOX: + Add_by_range(root, operation.boxpoint, false); + break; + case DELETE_POINT: + Delete_by_point(root, operation.point, false); + break; + case DELETE_BOX: + Delete_by_range(root, operation.boxpoint, false, false); + break; + case DOWNSAMPLE_DELETE: + Delete_by_range(root, operation.boxpoint, false, true); + break; + case PUSH_DOWN: + (*root)->tree_downsample_deleted |= operation.tree_downsample_deleted; + (*root)->point_downsample_deleted |= operation.tree_downsample_deleted; + (*root)->tree_deleted = + operation.tree_deleted || (*root)->tree_downsample_deleted; + (*root)->point_deleted = + (*root)->tree_deleted || (*root)->point_downsample_deleted; + if (operation.tree_downsample_deleted) + (*root)->down_del_num = (*root)->TreeSize; + if (operation.tree_deleted) + (*root)->invalid_point_num = (*root)->TreeSize; + else + (*root)->invalid_point_num = (*root)->down_del_num; + (*root)->need_push_down_to_left = true; + (*root)->need_push_down_to_right = true; + break; + default: + break; + } +} + +void KD_TREE::Build(PointVector point_cloud) { + if (Root_Node != nullptr) { + delete_tree_nodes(&Root_Node); + } + if (point_cloud.size() == 0) + return; + STATIC_ROOT_NODE = new KD_TREE_NODE; + InitTreeNode(STATIC_ROOT_NODE); + BuildTree( + &STATIC_ROOT_NODE->left_son_ptr, 0, point_cloud.size() - 1, point_cloud); + Update(STATIC_ROOT_NODE); + STATIC_ROOT_NODE->TreeSize = 0; + Root_Node = STATIC_ROOT_NODE->left_son_ptr; +} + +void KD_TREE::Nearest_Search(PointType point, + int k_nearest, + PointVector& Nearest_Points, + vector& Point_Distance, + double max_dist) { + MANUAL_HEAP q(2 * k_nearest); + q.clear(); + vector().swap(Point_Distance); + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node) { + Search(Root_Node, k_nearest, point, q, max_dist); + } else { + pthread_mutex_lock(&search_flag_mutex); + while (search_mutex_counter == -1) { + pthread_mutex_unlock(&search_flag_mutex); + usleep(1); + pthread_mutex_lock(&search_flag_mutex); + } + search_mutex_counter += 1; + pthread_mutex_unlock(&search_flag_mutex); + Search(Root_Node, k_nearest, point, q, max_dist); + pthread_mutex_lock(&search_flag_mutex); + search_mutex_counter -= 1; + pthread_mutex_unlock(&search_flag_mutex); + } + int k_found = min(k_nearest, int(q.size())); + PointVector().swap(Nearest_Points); + vector().swap(Point_Distance); + for (int i = 0; i < k_found; i++) { + Nearest_Points.insert(Nearest_Points.begin(), q.top().point); + Point_Distance.insert(Point_Distance.begin(), q.top().dist); + q.pop(); + } + return; +} + +int KD_TREE::Add_Points(PointVector& PointToAdd, bool downsample_on) { + int NewPointSize = PointToAdd.size(); + int tree_size = size(); + BoxPointType Box_of_Point; + PointType downsample_result, mid_point; + bool downsample_switch = downsample_on && DOWNSAMPLE_SWITCH; + float min_dist, tmp_dist; + int tmp_counter = 0; + for (int i = 0; i < PointToAdd.size(); i++) { + if (downsample_switch) { + Box_of_Point.vertex_min[0] = + floor(PointToAdd[i].x / downsample_size) * downsample_size; + Box_of_Point.vertex_max[0] = Box_of_Point.vertex_min[0] + downsample_size; + Box_of_Point.vertex_min[1] = + floor(PointToAdd[i].y / downsample_size) * downsample_size; + Box_of_Point.vertex_max[1] = Box_of_Point.vertex_min[1] + downsample_size; + Box_of_Point.vertex_min[2] = + floor(PointToAdd[i].z / downsample_size) * downsample_size; + Box_of_Point.vertex_max[2] = Box_of_Point.vertex_min[2] + downsample_size; + mid_point.x = Box_of_Point.vertex_min[0] + + (Box_of_Point.vertex_max[0] - Box_of_Point.vertex_min[0]) / 2.0; + mid_point.y = Box_of_Point.vertex_min[1] + + (Box_of_Point.vertex_max[1] - Box_of_Point.vertex_min[1]) / 2.0; + mid_point.z = Box_of_Point.vertex_min[2] + + (Box_of_Point.vertex_max[2] - Box_of_Point.vertex_min[2]) / 2.0; + PointVector().swap(Downsample_Storage); + Search_by_range(Root_Node, Box_of_Point, Downsample_Storage); + min_dist = calc_dist(PointToAdd[i], mid_point); + downsample_result = PointToAdd[i]; + for (int index = 0; index < Downsample_Storage.size(); index++) { + tmp_dist = calc_dist(Downsample_Storage[index], mid_point); + if (tmp_dist < min_dist) { + min_dist = tmp_dist; + downsample_result = Downsample_Storage[index]; + } + } + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node) { + if (Downsample_Storage.size() > 1 || + same_point(PointToAdd[i], downsample_result)) { + if (Downsample_Storage.size() > 0) + Delete_by_range(&Root_Node, Box_of_Point, true, true); + Add_by_point( + &Root_Node, downsample_result, true, Root_Node->division_axis); + tmp_counter++; + } + } else { + if (Downsample_Storage.size() > 1 || + same_point(PointToAdd[i], downsample_result)) { + Operation_Logger_Type operation_delete, operation; + operation_delete.boxpoint = Box_of_Point; + operation_delete.op = DOWNSAMPLE_DELETE; + operation.point = downsample_result; + operation.op = ADD_POINT; + pthread_mutex_lock(&working_flag_mutex); + if (Downsample_Storage.size() > 0) + Delete_by_range(&Root_Node, Box_of_Point, false, true); + Add_by_point( + &Root_Node, downsample_result, false, Root_Node->division_axis); + tmp_counter++; + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + if (Downsample_Storage.size() > 0) + Rebuild_Logger.push(operation_delete); + Rebuild_Logger.push(operation); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + }; + } + } else { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node) { + Add_by_point(&Root_Node, PointToAdd[i], true, Root_Node->division_axis); + } else { + Operation_Logger_Type operation; + operation.point = PointToAdd[i]; + operation.op = ADD_POINT; + pthread_mutex_lock(&working_flag_mutex); + Add_by_point( + &Root_Node, PointToAdd[i], false, Root_Node->division_axis); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(operation); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + } + } + return tmp_counter; +} + +void KD_TREE::Add_Point_Boxes(vector& BoxPoints) { + for (int i = 0; i < BoxPoints.size(); i++) { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node) { + Add_by_range(&Root_Node, BoxPoints[i], true); + } else { + Operation_Logger_Type operation; + operation.boxpoint = BoxPoints[i]; + operation.op = ADD_BOX; + pthread_mutex_lock(&working_flag_mutex); + Add_by_range(&Root_Node, BoxPoints[i], false); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(operation); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + } + return; +} + +void KD_TREE::Delete_Points(PointVector& PointToDel) { + for (int i = 0; i < PointToDel.size(); i++) { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node) { + Delete_by_point(&Root_Node, PointToDel[i], true); + } else { + Operation_Logger_Type operation; + operation.point = PointToDel[i]; + operation.op = DELETE_POINT; + pthread_mutex_lock(&working_flag_mutex); + Delete_by_point(&Root_Node, PointToDel[i], false); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(operation); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + } + return; +} + +int KD_TREE::Delete_Point_Boxes(vector& BoxPoints) { + int tmp_counter = 0; + for (int i = 0; i < BoxPoints.size(); i++) { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != Root_Node) { + tmp_counter += Delete_by_range(&Root_Node, BoxPoints[i], true, false); + } else { + Operation_Logger_Type operation; + operation.boxpoint = BoxPoints[i]; + operation.op = DELETE_BOX; + pthread_mutex_lock(&working_flag_mutex); + tmp_counter += Delete_by_range(&Root_Node, BoxPoints[i], false, false); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(operation); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + } + return tmp_counter; +} + +void KD_TREE::acquire_removed_points(PointVector& removed_points) { + pthread_mutex_lock(&points_deleted_rebuild_mutex_lock); + for (int i = 0; i < Points_deleted.size(); i++) { + removed_points.push_back(Points_deleted[i]); + } + for (int i = 0; i < Multithread_Points_deleted.size(); i++) { + removed_points.push_back(Multithread_Points_deleted[i]); + } + Points_deleted.clear(); + Multithread_Points_deleted.clear(); + pthread_mutex_unlock(&points_deleted_rebuild_mutex_lock); + return; +} + +void KD_TREE::BuildTree(KD_TREE_NODE** root, + int l, + int r, + PointVector& Storage) { + if (l > r) + return; + *root = new KD_TREE_NODE; + InitTreeNode(*root); + int mid = (l + r) >> 1; + int div_axis = 0; + int i; + // Find the best division Axis + float min_value[3] = {INFINITY, INFINITY, INFINITY}; + float max_value[3] = {-INFINITY, -INFINITY, -INFINITY}; + float dim_range[3] = {0, 0, 0}; + for (i = l; i <= r; i++) { + min_value[0] = min(min_value[0], Storage[i].x); + min_value[1] = min(min_value[1], Storage[i].y); + min_value[2] = min(min_value[2], Storage[i].z); + max_value[0] = max(max_value[0], Storage[i].x); + max_value[1] = max(max_value[1], Storage[i].y); + max_value[2] = max(max_value[2], Storage[i].z); + } + // Select the longest dimension as division axis + for (i = 0; i < 3; i++) + dim_range[i] = max_value[i] - min_value[i]; + for (i = 1; i < 3; i++) + if (dim_range[i] > dim_range[div_axis]) + div_axis = i; + // Divide by the division axis and recursively build. + + (*root)->division_axis = div_axis; + switch (div_axis) { + case 0: + nth_element(begin(Storage) + l, + begin(Storage) + mid, + begin(Storage) + r + 1, + point_cmp_x); + break; + case 1: + nth_element(begin(Storage) + l, + begin(Storage) + mid, + begin(Storage) + r + 1, + point_cmp_y); + break; + case 2: + nth_element(begin(Storage) + l, + begin(Storage) + mid, + begin(Storage) + r + 1, + point_cmp_z); + break; + default: + nth_element(begin(Storage) + l, + begin(Storage) + mid, + begin(Storage) + r + 1, + point_cmp_x); + break; + } + (*root)->point = Storage[mid]; + KD_TREE_NODE *left_son = nullptr, *right_son = nullptr; + BuildTree(&left_son, l, mid - 1, Storage); + BuildTree(&right_son, mid + 1, r, Storage); + (*root)->left_son_ptr = left_son; + (*root)->right_son_ptr = right_son; + Update((*root)); + return; +} + +void KD_TREE::Rebuild(KD_TREE_NODE** root) { + KD_TREE_NODE* father_ptr; + if ((*root)->TreeSize >= Multi_Thread_Rebuild_Point_Num) { + if (!pthread_mutex_trylock(&rebuild_ptr_mutex_lock)) { + if (Rebuild_Ptr == nullptr || + ((*root)->TreeSize > (*Rebuild_Ptr)->TreeSize)) { + Rebuild_Ptr = root; + } + pthread_mutex_unlock(&rebuild_ptr_mutex_lock); + } + } else { + father_ptr = (*root)->father_ptr; + int size_rec = (*root)->TreeSize; + PCL_Storage.clear(); + flatten(*root, PCL_Storage, DELETE_POINTS_REC); + delete_tree_nodes(root); + BuildTree(root, 0, PCL_Storage.size() - 1, PCL_Storage); + if (*root != nullptr) + (*root)->father_ptr = father_ptr; + if (*root == Root_Node) + STATIC_ROOT_NODE->left_son_ptr = *root; + } + return; +} + +int KD_TREE::Delete_by_range(KD_TREE_NODE** root, + BoxPointType boxpoint, + bool allow_rebuild, + bool is_downsample) { + if ((*root) == nullptr || (*root)->tree_deleted) + return 0; + (*root)->working_flag = true; + Push_Down(*root); + int tmp_counter = 0; + if (boxpoint.vertex_max[0] <= (*root)->node_range_x[0] || + boxpoint.vertex_min[0] > (*root)->node_range_x[1]) + return 0; + if (boxpoint.vertex_max[1] <= (*root)->node_range_y[0] || + boxpoint.vertex_min[1] > (*root)->node_range_y[1]) + return 0; + if (boxpoint.vertex_max[2] <= (*root)->node_range_z[0] || + boxpoint.vertex_min[2] > (*root)->node_range_z[1]) + return 0; + if (boxpoint.vertex_min[0] <= (*root)->node_range_x[0] && + boxpoint.vertex_max[0] > (*root)->node_range_x[1] && + boxpoint.vertex_min[1] <= (*root)->node_range_y[0] && + boxpoint.vertex_max[1] > (*root)->node_range_y[1] && + boxpoint.vertex_min[2] <= (*root)->node_range_z[0] && + boxpoint.vertex_max[2] > (*root)->node_range_z[1]) { + (*root)->tree_deleted = true; + (*root)->point_deleted = true; + (*root)->need_push_down_to_left = true; + (*root)->need_push_down_to_right = true; + tmp_counter = (*root)->TreeSize - (*root)->invalid_point_num; + (*root)->invalid_point_num = (*root)->TreeSize; + if (is_downsample) { + (*root)->tree_downsample_deleted = true; + (*root)->point_downsample_deleted = true; + (*root)->down_del_num = (*root)->TreeSize; + } + return tmp_counter; + } + if (!(*root)->point_deleted && boxpoint.vertex_min[0] <= (*root)->point.x && + boxpoint.vertex_max[0] > (*root)->point.x && + boxpoint.vertex_min[1] <= (*root)->point.y && + boxpoint.vertex_max[1] > (*root)->point.y && + boxpoint.vertex_min[2] <= (*root)->point.z && + boxpoint.vertex_max[2] > (*root)->point.z) { + (*root)->point_deleted = true; + tmp_counter += 1; + if (is_downsample) + (*root)->point_downsample_deleted = true; + } + Operation_Logger_Type delete_box_log; + struct timespec Timeout; + if (is_downsample) + delete_box_log.op = DOWNSAMPLE_DELETE; + else + delete_box_log.op = DELETE_BOX; + delete_box_log.boxpoint = boxpoint; + if ((Rebuild_Ptr == nullptr) || (*root)->left_son_ptr != *Rebuild_Ptr) { + tmp_counter += Delete_by_range( + &((*root)->left_son_ptr), boxpoint, allow_rebuild, is_downsample); + } else { + pthread_mutex_lock(&working_flag_mutex); + tmp_counter += Delete_by_range( + &((*root)->left_son_ptr), boxpoint, false, is_downsample); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(delete_box_log); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + if ((Rebuild_Ptr == nullptr) || (*root)->right_son_ptr != *Rebuild_Ptr) { + tmp_counter += Delete_by_range( + &((*root)->right_son_ptr), boxpoint, allow_rebuild, is_downsample); + } else { + pthread_mutex_lock(&working_flag_mutex); + tmp_counter += Delete_by_range( + &((*root)->right_son_ptr), boxpoint, false, is_downsample); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(delete_box_log); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + Update(*root); + if (Rebuild_Ptr != nullptr && *Rebuild_Ptr == *root && + (*root)->TreeSize < Multi_Thread_Rebuild_Point_Num) + Rebuild_Ptr = nullptr; + bool need_rebuild = allow_rebuild & Criterion_Check((*root)); + if (need_rebuild) + Rebuild(root); + if ((*root) != nullptr) + (*root)->working_flag = false; + return tmp_counter; +} + +void KD_TREE::Delete_by_point(KD_TREE_NODE** root, + PointType point, + bool allow_rebuild) { + if ((*root) == nullptr || (*root)->tree_deleted) + return; + (*root)->working_flag = true; + Push_Down(*root); + if (same_point((*root)->point, point) && !(*root)->point_deleted) { + (*root)->point_deleted = true; + (*root)->invalid_point_num += 1; + if ((*root)->invalid_point_num == (*root)->TreeSize) + (*root)->tree_deleted = true; + return; + } + Operation_Logger_Type delete_log; + struct timespec Timeout; + delete_log.op = DELETE_POINT; + delete_log.point = point; + if (((*root)->division_axis == 0 && point.x < (*root)->point.x) || + ((*root)->division_axis == 1 && point.y < (*root)->point.y) || + ((*root)->division_axis == 2 && point.z < (*root)->point.z)) { + if ((Rebuild_Ptr == nullptr) || (*root)->left_son_ptr != *Rebuild_Ptr) { + Delete_by_point(&(*root)->left_son_ptr, point, allow_rebuild); + } else { + pthread_mutex_lock(&working_flag_mutex); + Delete_by_point(&(*root)->left_son_ptr, point, false); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(delete_log); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + } else { + if ((Rebuild_Ptr == nullptr) || (*root)->right_son_ptr != *Rebuild_Ptr) { + Delete_by_point(&(*root)->right_son_ptr, point, allow_rebuild); + } else { + pthread_mutex_lock(&working_flag_mutex); + Delete_by_point(&(*root)->right_son_ptr, point, false); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(delete_log); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + } + Update(*root); + if (Rebuild_Ptr != nullptr && *Rebuild_Ptr == *root && + (*root)->TreeSize < Multi_Thread_Rebuild_Point_Num) + Rebuild_Ptr = nullptr; + bool need_rebuild = allow_rebuild & Criterion_Check((*root)); + if (need_rebuild) + Rebuild(root); + if ((*root) != nullptr) + (*root)->working_flag = false; + return; +} + +void KD_TREE::Add_by_range(KD_TREE_NODE** root, + BoxPointType boxpoint, + bool allow_rebuild) { + if ((*root) == nullptr) + return; + (*root)->working_flag = true; + Push_Down(*root); + if (boxpoint.vertex_max[0] <= (*root)->node_range_x[0] || + boxpoint.vertex_min[0] > (*root)->node_range_x[1]) + return; + if (boxpoint.vertex_max[1] <= (*root)->node_range_y[0] || + boxpoint.vertex_min[1] > (*root)->node_range_y[1]) + return; + if (boxpoint.vertex_max[2] <= (*root)->node_range_z[0] || + boxpoint.vertex_min[2] > (*root)->node_range_z[1]) + return; + if (boxpoint.vertex_min[0] <= (*root)->node_range_x[0] && + boxpoint.vertex_max[0] > (*root)->node_range_x[1] && + boxpoint.vertex_min[1] <= (*root)->node_range_y[0] && + boxpoint.vertex_max[1] > (*root)->node_range_y[1] && + boxpoint.vertex_min[2] <= (*root)->node_range_z[0] && + boxpoint.vertex_max[2] > (*root)->node_range_z[1]) { + (*root)->tree_deleted = false || (*root)->tree_downsample_deleted; + (*root)->point_deleted = false || (*root)->point_downsample_deleted; + (*root)->need_push_down_to_left = true; + (*root)->need_push_down_to_right = true; + (*root)->invalid_point_num = (*root)->down_del_num; + return; + } + if (boxpoint.vertex_min[0] <= (*root)->point.x && + boxpoint.vertex_max[0] > (*root)->point.x && + boxpoint.vertex_min[1] <= (*root)->point.y && + boxpoint.vertex_max[1] > (*root)->point.y && + boxpoint.vertex_min[2] <= (*root)->point.z && + boxpoint.vertex_max[2] > (*root)->point.z) { + (*root)->point_deleted = (*root)->point_downsample_deleted; + } + Operation_Logger_Type add_box_log; + struct timespec Timeout; + add_box_log.op = ADD_BOX; + add_box_log.boxpoint = boxpoint; + if ((Rebuild_Ptr == nullptr) || (*root)->left_son_ptr != *Rebuild_Ptr) { + Add_by_range(&((*root)->left_son_ptr), boxpoint, allow_rebuild); + } else { + pthread_mutex_lock(&working_flag_mutex); + Add_by_range(&((*root)->left_son_ptr), boxpoint, false); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(add_box_log); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + if ((Rebuild_Ptr == nullptr) || (*root)->right_son_ptr != *Rebuild_Ptr) { + Add_by_range(&((*root)->right_son_ptr), boxpoint, allow_rebuild); + } else { + pthread_mutex_lock(&working_flag_mutex); + Add_by_range(&((*root)->right_son_ptr), boxpoint, false); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(add_box_log); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + Update(*root); + if (Rebuild_Ptr != nullptr && *Rebuild_Ptr == *root && + (*root)->TreeSize < Multi_Thread_Rebuild_Point_Num) + Rebuild_Ptr = nullptr; + bool need_rebuild = allow_rebuild & Criterion_Check((*root)); + if (need_rebuild) + Rebuild(root); + if ((*root) != nullptr) + (*root)->working_flag = false; + return; +} + +void KD_TREE::Add_by_point(KD_TREE_NODE** root, + PointType point, + bool allow_rebuild, + int father_axis) { + if (*root == nullptr) { + *root = new KD_TREE_NODE; + InitTreeNode(*root); + (*root)->point = point; + (*root)->division_axis = (father_axis + 1) % 3; + Update(*root); + return; + } + (*root)->working_flag = true; + Operation_Logger_Type add_log; + struct timespec Timeout; + add_log.op = ADD_POINT; + add_log.point = point; + Push_Down(*root); + if (((*root)->division_axis == 0 && point.x < (*root)->point.x) || + ((*root)->division_axis == 1 && point.y < (*root)->point.y) || + ((*root)->division_axis == 2 && point.z < (*root)->point.z)) { + if ((Rebuild_Ptr == nullptr) || (*root)->left_son_ptr != *Rebuild_Ptr) { + Add_by_point( + &(*root)->left_son_ptr, point, allow_rebuild, (*root)->division_axis); + } else { + pthread_mutex_lock(&working_flag_mutex); + Add_by_point( + &(*root)->left_son_ptr, point, false, (*root)->division_axis); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(add_log); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + } else { + if ((Rebuild_Ptr == nullptr) || (*root)->right_son_ptr != *Rebuild_Ptr) { + Add_by_point(&(*root)->right_son_ptr, + point, + allow_rebuild, + (*root)->division_axis); + } else { + pthread_mutex_lock(&working_flag_mutex); + Add_by_point( + &(*root)->right_son_ptr, point, false, (*root)->division_axis); + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(add_log); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + pthread_mutex_unlock(&working_flag_mutex); + } + } + Update(*root); + if (Rebuild_Ptr != nullptr && *Rebuild_Ptr == *root && + (*root)->TreeSize < Multi_Thread_Rebuild_Point_Num) + Rebuild_Ptr = nullptr; + bool need_rebuild = allow_rebuild & Criterion_Check((*root)); + if (need_rebuild) + Rebuild(root); + if ((*root) != nullptr) + (*root)->working_flag = false; + return; +} + +void KD_TREE::Search(KD_TREE_NODE* root, + int k_nearest, + PointType point, + MANUAL_HEAP& q, + double max_dist) { + if (root == nullptr || root->tree_deleted) + return; + double cur_dist = calc_box_dist(root, point); + if (cur_dist > max_dist) + return; + int retval; + if (root->need_push_down_to_left || root->need_push_down_to_right) { + retval = pthread_mutex_trylock(&(root->push_down_mutex_lock)); + if (retval == 0) { + Push_Down(root); + pthread_mutex_unlock(&(root->push_down_mutex_lock)); + } else { + pthread_mutex_lock(&(root->push_down_mutex_lock)); + pthread_mutex_unlock(&(root->push_down_mutex_lock)); + } + } + if (!root->point_deleted) { + float dist = calc_dist(point, root->point); + if (dist <= max_dist && (q.size() < k_nearest || dist < q.top().dist)) { + if (q.size() >= k_nearest) + q.pop(); + PointType_CMP current_point{root->point, dist}; + q.push(current_point); + } + } + int cur_search_counter; + float dist_left_node = calc_box_dist(root->left_son_ptr, point); + float dist_right_node = calc_box_dist(root->right_son_ptr, point); + if (q.size() < k_nearest || + dist_left_node < q.top().dist && dist_right_node < q.top().dist) { + if (dist_left_node <= dist_right_node) { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->left_son_ptr) { + Search(root->left_son_ptr, k_nearest, point, q, max_dist); + } else { + pthread_mutex_lock(&search_flag_mutex); + while (search_mutex_counter == -1) { + pthread_mutex_unlock(&search_flag_mutex); + usleep(1); + pthread_mutex_lock(&search_flag_mutex); + } + search_mutex_counter += 1; + pthread_mutex_unlock(&search_flag_mutex); + Search(root->left_son_ptr, k_nearest, point, q, max_dist); + pthread_mutex_lock(&search_flag_mutex); + search_mutex_counter -= 1; + pthread_mutex_unlock(&search_flag_mutex); + } + if (q.size() < k_nearest || dist_right_node < q.top().dist) { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->right_son_ptr) { + Search(root->right_son_ptr, k_nearest, point, q, max_dist); + } else { + pthread_mutex_lock(&search_flag_mutex); + while (search_mutex_counter == -1) { + pthread_mutex_unlock(&search_flag_mutex); + usleep(1); + pthread_mutex_lock(&search_flag_mutex); + } + search_mutex_counter += 1; + pthread_mutex_unlock(&search_flag_mutex); + Search(root->right_son_ptr, k_nearest, point, q, max_dist); + pthread_mutex_lock(&search_flag_mutex); + search_mutex_counter -= 1; + pthread_mutex_unlock(&search_flag_mutex); + } + } + } else { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->right_son_ptr) { + Search(root->right_son_ptr, k_nearest, point, q, max_dist); + } else { + pthread_mutex_lock(&search_flag_mutex); + while (search_mutex_counter == -1) { + pthread_mutex_unlock(&search_flag_mutex); + usleep(1); + pthread_mutex_lock(&search_flag_mutex); + } + search_mutex_counter += 1; + pthread_mutex_unlock(&search_flag_mutex); + Search(root->right_son_ptr, k_nearest, point, q, max_dist); + pthread_mutex_lock(&search_flag_mutex); + search_mutex_counter -= 1; + pthread_mutex_unlock(&search_flag_mutex); + } + if (q.size() < k_nearest || dist_left_node < q.top().dist) { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->left_son_ptr) { + Search(root->left_son_ptr, k_nearest, point, q, max_dist); + } else { + pthread_mutex_lock(&search_flag_mutex); + while (search_mutex_counter == -1) { + pthread_mutex_unlock(&search_flag_mutex); + usleep(1); + pthread_mutex_lock(&search_flag_mutex); + } + search_mutex_counter += 1; + pthread_mutex_unlock(&search_flag_mutex); + Search(root->left_son_ptr, k_nearest, point, q, max_dist); + pthread_mutex_lock(&search_flag_mutex); + search_mutex_counter -= 1; + pthread_mutex_unlock(&search_flag_mutex); + } + } + } + } else { + if (dist_left_node < q.top().dist) { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->left_son_ptr) { + Search(root->left_son_ptr, k_nearest, point, q, max_dist); + } else { + pthread_mutex_lock(&search_flag_mutex); + while (search_mutex_counter == -1) { + pthread_mutex_unlock(&search_flag_mutex); + usleep(1); + pthread_mutex_lock(&search_flag_mutex); + } + search_mutex_counter += 1; + pthread_mutex_unlock(&search_flag_mutex); + Search(root->left_son_ptr, k_nearest, point, q, max_dist); + pthread_mutex_lock(&search_flag_mutex); + search_mutex_counter -= 1; + pthread_mutex_unlock(&search_flag_mutex); + } + } + if (dist_right_node < q.top().dist) { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->right_son_ptr) { + Search(root->right_son_ptr, k_nearest, point, q, max_dist); + } else { + pthread_mutex_lock(&search_flag_mutex); + while (search_mutex_counter == -1) { + pthread_mutex_unlock(&search_flag_mutex); + usleep(1); + pthread_mutex_lock(&search_flag_mutex); + } + search_mutex_counter += 1; + pthread_mutex_unlock(&search_flag_mutex); + Search(root->right_son_ptr, k_nearest, point, q, max_dist); + pthread_mutex_lock(&search_flag_mutex); + search_mutex_counter -= 1; + pthread_mutex_unlock(&search_flag_mutex); + } + } + } + return; +} + +void KD_TREE::Search_by_range(KD_TREE_NODE* root, + BoxPointType boxpoint, + PointVector& Storage) { + if (root == nullptr) + return; + Push_Down(root); + if (boxpoint.vertex_max[0] <= root->node_range_x[0] || + boxpoint.vertex_min[0] > root->node_range_x[1]) + return; + if (boxpoint.vertex_max[1] <= root->node_range_y[0] || + boxpoint.vertex_min[1] > root->node_range_y[1]) + return; + if (boxpoint.vertex_max[2] <= root->node_range_z[0] || + boxpoint.vertex_min[2] > root->node_range_z[1]) + return; + if (boxpoint.vertex_min[0] <= root->node_range_x[0] && + boxpoint.vertex_max[0] > root->node_range_x[1] && + boxpoint.vertex_min[1] <= root->node_range_y[0] && + boxpoint.vertex_max[1] > root->node_range_y[1] && + boxpoint.vertex_min[2] <= root->node_range_z[0] && + boxpoint.vertex_max[2] > root->node_range_z[1]) { + flatten(root, Storage, NOT_RECORD); + return; + } + if (boxpoint.vertex_min[0] <= root->point.x && + boxpoint.vertex_max[0] > root->point.x && + boxpoint.vertex_min[1] <= root->point.y && + boxpoint.vertex_max[1] > root->point.y && + boxpoint.vertex_min[2] <= root->point.z && + boxpoint.vertex_max[2] > root->point.z) { + if (!root->point_deleted) + Storage.push_back(root->point); + } + if ((Rebuild_Ptr == nullptr) || root->left_son_ptr != *Rebuild_Ptr) { + Search_by_range(root->left_son_ptr, boxpoint, Storage); + } else { + pthread_mutex_lock(&search_flag_mutex); + Search_by_range(root->left_son_ptr, boxpoint, Storage); + pthread_mutex_unlock(&search_flag_mutex); + } + if ((Rebuild_Ptr == nullptr) || root->right_son_ptr != *Rebuild_Ptr) { + Search_by_range(root->right_son_ptr, boxpoint, Storage); + } else { + pthread_mutex_lock(&search_flag_mutex); + Search_by_range(root->right_son_ptr, boxpoint, Storage); + pthread_mutex_unlock(&search_flag_mutex); + } + return; +} + +bool KD_TREE::Criterion_Check(KD_TREE_NODE* root) { + if (root->TreeSize <= Minimal_Unbalanced_Tree_Size) { + return false; + } + float balance_evaluation = 0.0f; + float delete_evaluation = 0.0f; + KD_TREE_NODE* son_ptr = root->left_son_ptr; + if (son_ptr == nullptr) + son_ptr = root->right_son_ptr; + delete_evaluation = float(root->invalid_point_num) / root->TreeSize; + balance_evaluation = float(son_ptr->TreeSize) / (root->TreeSize - 1); + if (delete_evaluation > delete_criterion_param) { + return true; + } + if (balance_evaluation > balance_criterion_param || + balance_evaluation < 1 - balance_criterion_param) { + return true; + } + return false; +} + +void KD_TREE::Push_Down(KD_TREE_NODE* root) { + if (root == nullptr) + return; + Operation_Logger_Type operation; + operation.op = PUSH_DOWN; + operation.tree_deleted = root->tree_deleted; + operation.tree_downsample_deleted = root->tree_downsample_deleted; + if (root->need_push_down_to_left && root->left_son_ptr != nullptr) { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->left_son_ptr) { + root->left_son_ptr->tree_downsample_deleted |= + root->tree_downsample_deleted; + root->left_son_ptr->point_downsample_deleted |= + root->tree_downsample_deleted; + root->left_son_ptr->tree_deleted = + root->tree_deleted || root->left_son_ptr->tree_downsample_deleted; + root->left_son_ptr->point_deleted = root->left_son_ptr->tree_deleted || + root->left_son_ptr->point_downsample_deleted; + if (root->tree_downsample_deleted) + root->left_son_ptr->down_del_num = root->left_son_ptr->TreeSize; + if (root->tree_deleted) + root->left_son_ptr->invalid_point_num = root->left_son_ptr->TreeSize; + else + root->left_son_ptr->invalid_point_num = + root->left_son_ptr->down_del_num; + root->left_son_ptr->need_push_down_to_left = true; + root->left_son_ptr->need_push_down_to_right = true; + root->need_push_down_to_left = false; + } else { + pthread_mutex_lock(&working_flag_mutex); + root->left_son_ptr->tree_downsample_deleted |= + root->tree_downsample_deleted; + root->left_son_ptr->point_downsample_deleted |= + root->tree_downsample_deleted; + root->left_son_ptr->tree_deleted = + root->tree_deleted || root->left_son_ptr->tree_downsample_deleted; + root->left_son_ptr->point_deleted = root->left_son_ptr->tree_deleted || + root->left_son_ptr->point_downsample_deleted; + if (root->tree_downsample_deleted) + root->left_son_ptr->down_del_num = root->left_son_ptr->TreeSize; + if (root->tree_deleted) + root->left_son_ptr->invalid_point_num = root->left_son_ptr->TreeSize; + else + root->left_son_ptr->invalid_point_num = + root->left_son_ptr->down_del_num; + root->left_son_ptr->need_push_down_to_left = true; + root->left_son_ptr->need_push_down_to_right = true; + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(operation); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + root->need_push_down_to_left = false; + pthread_mutex_unlock(&working_flag_mutex); + } + } + if (root->need_push_down_to_right && root->right_son_ptr != nullptr) { + if (Rebuild_Ptr == nullptr || *Rebuild_Ptr != root->right_son_ptr) { + root->right_son_ptr->tree_downsample_deleted |= + root->tree_downsample_deleted; + root->right_son_ptr->point_downsample_deleted |= + root->tree_downsample_deleted; + root->right_son_ptr->tree_deleted = + root->tree_deleted || root->right_son_ptr->tree_downsample_deleted; + root->right_son_ptr->point_deleted = root->right_son_ptr->tree_deleted || + root->right_son_ptr->point_downsample_deleted; + if (root->tree_downsample_deleted) + root->right_son_ptr->down_del_num = root->right_son_ptr->TreeSize; + if (root->tree_deleted) + root->right_son_ptr->invalid_point_num = root->right_son_ptr->TreeSize; + else + root->right_son_ptr->invalid_point_num = + root->right_son_ptr->down_del_num; + root->right_son_ptr->need_push_down_to_left = true; + root->right_son_ptr->need_push_down_to_right = true; + root->need_push_down_to_right = false; + } else { + pthread_mutex_lock(&working_flag_mutex); + root->right_son_ptr->tree_downsample_deleted |= + root->tree_downsample_deleted; + root->right_son_ptr->point_downsample_deleted |= + root->tree_downsample_deleted; + root->right_son_ptr->tree_deleted = + root->tree_deleted || root->right_son_ptr->tree_downsample_deleted; + root->right_son_ptr->point_deleted = root->right_son_ptr->tree_deleted || + root->right_son_ptr->point_downsample_deleted; + if (root->tree_downsample_deleted) + root->right_son_ptr->down_del_num = root->right_son_ptr->TreeSize; + if (root->tree_deleted) + root->right_son_ptr->invalid_point_num = root->right_son_ptr->TreeSize; + else + root->right_son_ptr->invalid_point_num = + root->right_son_ptr->down_del_num; + root->right_son_ptr->need_push_down_to_left = true; + root->right_son_ptr->need_push_down_to_right = true; + if (rebuild_flag) { + pthread_mutex_lock(&rebuild_logger_mutex_lock); + Rebuild_Logger.push(operation); + pthread_mutex_unlock(&rebuild_logger_mutex_lock); + } + root->need_push_down_to_right = false; + pthread_mutex_unlock(&working_flag_mutex); + } + } + return; +} + +void KD_TREE::Update(KD_TREE_NODE* root) { + KD_TREE_NODE* left_son_ptr = root->left_son_ptr; + KD_TREE_NODE* right_son_ptr = root->right_son_ptr; + float tmp_range_x[2] = {INFINITY, -INFINITY}; + float tmp_range_y[2] = {INFINITY, -INFINITY}; + float tmp_range_z[2] = {INFINITY, -INFINITY}; + // Update Tree Size + if (left_son_ptr != nullptr && right_son_ptr != nullptr) { + root->TreeSize = left_son_ptr->TreeSize + right_son_ptr->TreeSize + 1; + root->invalid_point_num = left_son_ptr->invalid_point_num + + right_son_ptr->invalid_point_num + (root->point_deleted ? 1 : 0); + root->down_del_num = left_son_ptr->down_del_num + + right_son_ptr->down_del_num + (root->point_downsample_deleted ? 1 : 0); + root->tree_downsample_deleted = left_son_ptr->tree_downsample_deleted & + right_son_ptr->tree_downsample_deleted & root->point_downsample_deleted; + root->tree_deleted = left_son_ptr->tree_deleted && + right_son_ptr->tree_deleted && root->point_deleted; + if (root->tree_deleted || + (!left_son_ptr->tree_deleted && !right_son_ptr->tree_deleted && + !root->point_deleted)) { + tmp_range_x[0] = min( + min(left_son_ptr->node_range_x[0], right_son_ptr->node_range_x[0]), + root->point.x); + tmp_range_x[1] = max( + max(left_son_ptr->node_range_x[1], right_son_ptr->node_range_x[1]), + root->point.x); + tmp_range_y[0] = min( + min(left_son_ptr->node_range_y[0], right_son_ptr->node_range_y[0]), + root->point.y); + tmp_range_y[1] = max( + max(left_son_ptr->node_range_y[1], right_son_ptr->node_range_y[1]), + root->point.y); + tmp_range_z[0] = min( + min(left_son_ptr->node_range_z[0], right_son_ptr->node_range_z[0]), + root->point.z); + tmp_range_z[1] = max( + max(left_son_ptr->node_range_z[1], right_son_ptr->node_range_z[1]), + root->point.z); + } else { + if (!left_son_ptr->tree_deleted) { + tmp_range_x[0] = min(tmp_range_x[0], left_son_ptr->node_range_x[0]); + tmp_range_x[1] = max(tmp_range_x[1], left_son_ptr->node_range_x[1]); + tmp_range_y[0] = min(tmp_range_y[0], left_son_ptr->node_range_y[0]); + tmp_range_y[1] = max(tmp_range_y[1], left_son_ptr->node_range_y[1]); + tmp_range_z[0] = min(tmp_range_z[0], left_son_ptr->node_range_z[0]); + tmp_range_z[1] = max(tmp_range_z[1], left_son_ptr->node_range_z[1]); + } + if (!right_son_ptr->tree_deleted) { + tmp_range_x[0] = min(tmp_range_x[0], right_son_ptr->node_range_x[0]); + tmp_range_x[1] = max(tmp_range_x[1], right_son_ptr->node_range_x[1]); + tmp_range_y[0] = min(tmp_range_y[0], right_son_ptr->node_range_y[0]); + tmp_range_y[1] = max(tmp_range_y[1], right_son_ptr->node_range_y[1]); + tmp_range_z[0] = min(tmp_range_z[0], right_son_ptr->node_range_z[0]); + tmp_range_z[1] = max(tmp_range_z[1], right_son_ptr->node_range_z[1]); + } + if (!root->point_deleted) { + tmp_range_x[0] = min(tmp_range_x[0], root->point.x); + tmp_range_x[1] = max(tmp_range_x[1], root->point.x); + tmp_range_y[0] = min(tmp_range_y[0], root->point.y); + tmp_range_y[1] = max(tmp_range_y[1], root->point.y); + tmp_range_z[0] = min(tmp_range_z[0], root->point.z); + tmp_range_z[1] = max(tmp_range_z[1], root->point.z); + } + } + } else if (left_son_ptr != nullptr) { + root->TreeSize = left_son_ptr->TreeSize + 1; + root->invalid_point_num = + left_son_ptr->invalid_point_num + (root->point_deleted ? 1 : 0); + root->down_del_num = + left_son_ptr->down_del_num + (root->point_downsample_deleted ? 1 : 0); + root->tree_downsample_deleted = + left_son_ptr->tree_downsample_deleted & root->point_downsample_deleted; + root->tree_deleted = left_son_ptr->tree_deleted && root->point_deleted; + if (root->tree_deleted || + (!left_son_ptr->tree_deleted && !root->point_deleted)) { + tmp_range_x[0] = min(left_son_ptr->node_range_x[0], root->point.x); + tmp_range_x[1] = max(left_son_ptr->node_range_x[1], root->point.x); + tmp_range_y[0] = min(left_son_ptr->node_range_y[0], root->point.y); + tmp_range_y[1] = max(left_son_ptr->node_range_y[1], root->point.y); + tmp_range_z[0] = min(left_son_ptr->node_range_z[0], root->point.z); + tmp_range_z[1] = max(left_son_ptr->node_range_z[1], root->point.z); + } else { + if (!left_son_ptr->tree_deleted) { + tmp_range_x[0] = min(tmp_range_x[0], left_son_ptr->node_range_x[0]); + tmp_range_x[1] = max(tmp_range_x[1], left_son_ptr->node_range_x[1]); + tmp_range_y[0] = min(tmp_range_y[0], left_son_ptr->node_range_y[0]); + tmp_range_y[1] = max(tmp_range_y[1], left_son_ptr->node_range_y[1]); + tmp_range_z[0] = min(tmp_range_z[0], left_son_ptr->node_range_z[0]); + tmp_range_z[1] = max(tmp_range_z[1], left_son_ptr->node_range_z[1]); + } + if (!root->point_deleted) { + tmp_range_x[0] = min(tmp_range_x[0], root->point.x); + tmp_range_x[1] = max(tmp_range_x[1], root->point.x); + tmp_range_y[0] = min(tmp_range_y[0], root->point.y); + tmp_range_y[1] = max(tmp_range_y[1], root->point.y); + tmp_range_z[0] = min(tmp_range_z[0], root->point.z); + tmp_range_z[1] = max(tmp_range_z[1], root->point.z); + } + } + + } else if (right_son_ptr != nullptr) { + root->TreeSize = right_son_ptr->TreeSize + 1; + root->invalid_point_num = + right_son_ptr->invalid_point_num + (root->point_deleted ? 1 : 0); + root->down_del_num = + right_son_ptr->down_del_num + (root->point_downsample_deleted ? 1 : 0); + root->tree_downsample_deleted = + right_son_ptr->tree_downsample_deleted & root->point_downsample_deleted; + root->tree_deleted = right_son_ptr->tree_deleted && root->point_deleted; + if (root->tree_deleted || + (!right_son_ptr->tree_deleted && !root->point_deleted)) { + tmp_range_x[0] = min(right_son_ptr->node_range_x[0], root->point.x); + tmp_range_x[1] = max(right_son_ptr->node_range_x[1], root->point.x); + tmp_range_y[0] = min(right_son_ptr->node_range_y[0], root->point.y); + tmp_range_y[1] = max(right_son_ptr->node_range_y[1], root->point.y); + tmp_range_z[0] = min(right_son_ptr->node_range_z[0], root->point.z); + tmp_range_z[1] = max(right_son_ptr->node_range_z[1], root->point.z); + } else { + if (!right_son_ptr->tree_deleted) { + tmp_range_x[0] = min(tmp_range_x[0], right_son_ptr->node_range_x[0]); + tmp_range_x[1] = max(tmp_range_x[1], right_son_ptr->node_range_x[1]); + tmp_range_y[0] = min(tmp_range_y[0], right_son_ptr->node_range_y[0]); + tmp_range_y[1] = max(tmp_range_y[1], right_son_ptr->node_range_y[1]); + tmp_range_z[0] = min(tmp_range_z[0], right_son_ptr->node_range_z[0]); + tmp_range_z[1] = max(tmp_range_z[1], right_son_ptr->node_range_z[1]); + } + if (!root->point_deleted) { + tmp_range_x[0] = min(tmp_range_x[0], root->point.x); + tmp_range_x[1] = max(tmp_range_x[1], root->point.x); + tmp_range_y[0] = min(tmp_range_y[0], root->point.y); + tmp_range_y[1] = max(tmp_range_y[1], root->point.y); + tmp_range_z[0] = min(tmp_range_z[0], root->point.z); + tmp_range_z[1] = max(tmp_range_z[1], root->point.z); + } + } + } else { + root->TreeSize = 1; + root->invalid_point_num = (root->point_deleted ? 1 : 0); + root->down_del_num = (root->point_downsample_deleted ? 1 : 0); + root->tree_downsample_deleted = root->point_downsample_deleted; + root->tree_deleted = root->point_deleted; + tmp_range_x[0] = root->point.x; + tmp_range_x[1] = root->point.x; + tmp_range_y[0] = root->point.y; + tmp_range_y[1] = root->point.y; + tmp_range_z[0] = root->point.z; + tmp_range_z[1] = root->point.z; + } + memcpy(root->node_range_x, tmp_range_x, sizeof(tmp_range_x)); + memcpy(root->node_range_y, tmp_range_y, sizeof(tmp_range_y)); + memcpy(root->node_range_z, tmp_range_z, sizeof(tmp_range_z)); + if (left_son_ptr != nullptr) + left_son_ptr->father_ptr = root; + if (right_son_ptr != nullptr) + right_son_ptr->father_ptr = root; + if (root == Root_Node && root->TreeSize > 3) { + KD_TREE_NODE* son_ptr = root->left_son_ptr; + if (son_ptr == nullptr) + son_ptr = root->right_son_ptr; + float tmp_bal = float(son_ptr->TreeSize) / (root->TreeSize - 1); + root->alpha_del = float(root->invalid_point_num) / root->TreeSize; + root->alpha_bal = (tmp_bal >= 0.5 - EPSS) ? tmp_bal : 1 - tmp_bal; + } + return; +} + +void KD_TREE::flatten(KD_TREE_NODE* root, + PointVector& Storage, + delete_point_storage_set storage_type) { + if (root == nullptr) + return; + Push_Down(root); + if (!root->point_deleted) { + Storage.push_back(root->point); + } + flatten(root->left_son_ptr, Storage, storage_type); + flatten(root->right_son_ptr, Storage, storage_type); + switch (storage_type) { + case NOT_RECORD: + break; + case DELETE_POINTS_REC: + if (root->point_deleted && !root->point_downsample_deleted) { + Points_deleted.push_back(root->point); + } + break; + case MULTI_THREAD_REC: + if (root->point_deleted && !root->point_downsample_deleted) { + Multithread_Points_deleted.push_back(root->point); + } + break; + default: + break; + } + return; +} + +void KD_TREE::delete_tree_nodes(KD_TREE_NODE** root) { + if (*root == nullptr) + return; + Push_Down(*root); + delete_tree_nodes(&(*root)->left_son_ptr); + delete_tree_nodes(&(*root)->right_son_ptr); + + pthread_mutex_destroy(&(*root)->push_down_mutex_lock); + delete *root; + *root = nullptr; + + return; +} + +bool KD_TREE::same_point(PointType a, PointType b) { + return (fabs(a.x - b.x) < EPSS && fabs(a.y - b.y) < EPSS && + fabs(a.z - b.z) < EPSS); +} + +float KD_TREE::calc_dist(PointType a, PointType b) { + float dist = 0.0f; + dist = (a.x - b.x) * (a.x - b.x) + (a.y - b.y) * (a.y - b.y) + + (a.z - b.z) * (a.z - b.z); + return dist; +} + +float KD_TREE::calc_box_dist(KD_TREE_NODE* node, PointType point) { + if (node == nullptr) + return INFINITY; + float min_dist = 0.0; + if (point.x < node->node_range_x[0]) + min_dist += + (point.x - node->node_range_x[0]) * (point.x - node->node_range_x[0]); + if (point.x > node->node_range_x[1]) + min_dist += + (point.x - node->node_range_x[1]) * (point.x - node->node_range_x[1]); + if (point.y < node->node_range_y[0]) + min_dist += + (point.y - node->node_range_y[0]) * (point.y - node->node_range_y[0]); + if (point.y > node->node_range_y[1]) + min_dist += + (point.y - node->node_range_y[1]) * (point.y - node->node_range_y[1]); + if (point.z < node->node_range_z[0]) + min_dist += + (point.z - node->node_range_z[0]) * (point.z - node->node_range_z[0]); + if (point.z > node->node_range_z[1]) + min_dist += + (point.z - node->node_range_z[1]) * (point.z - node->node_range_z[1]); + return min_dist; +} + +bool KD_TREE::point_cmp_x(PointType a, PointType b) { + return a.x < b.x; +} +bool KD_TREE::point_cmp_y(PointType a, PointType b) { + return a.y < b.y; +} +bool KD_TREE::point_cmp_z(PointType a, PointType b) { + return a.z < b.z; +} + +// Manual heap +MANUAL_HEAP::MANUAL_HEAP(int max_capacity) { + cap = max_capacity; + heap = new PointType_CMP[max_capacity]; + heap_size = 0; +} + +MANUAL_HEAP::~MANUAL_HEAP() { + delete[] heap; +} + +void MANUAL_HEAP::pop() { + if (heap_size == 0) + return; + heap[0] = heap[heap_size - 1]; + heap_size--; + MoveDown(0); + return; +} + +PointType_CMP MANUAL_HEAP::top() { + return heap[0]; +} + +void MANUAL_HEAP::push(PointType_CMP point) { + if (heap_size >= cap) + return; + heap[heap_size] = point; + FloatUp(heap_size); + heap_size++; + return; +} + +int MANUAL_HEAP::size() { + return heap_size; +} + +void MANUAL_HEAP::clear() { + heap_size = 0; + return; +} + +void MANUAL_HEAP::MoveDown(int heap_index) { + int l = heap_index * 2 + 1; + PointType_CMP tmp = heap[heap_index]; + while (l < heap_size) { + if (l + 1 < heap_size && heap[l] < heap[l + 1]) + l++; + if (tmp < heap[l]) { + heap[heap_index] = heap[l]; + heap_index = l; + l = heap_index * 2 + 1; + } else + break; + } + heap[heap_index] = tmp; + return; +} + +void MANUAL_HEAP::FloatUp(int heap_index) { + int ancestor = (heap_index - 1) / 2; + PointType_CMP tmp = heap[heap_index]; + while (heap_index > 0) { + if (heap[ancestor] < tmp) { + heap[heap_index] = heap[ancestor]; + heap_index = ancestor; + ancestor = (heap_index - 1) / 2; + } else + break; + } + heap[heap_index] = tmp; + return; +} + +// manual queue +void MANUAL_Q::clear() { + head = 0; + tail = 0; + counter = 0; + is_empty = true; + return; +} + +void MANUAL_Q::pop() { + if (counter == 0) + return; + head++; + head %= Q_LEN; + counter--; + if (counter == 0) + is_empty = true; + return; +} + +Operation_Logger_Type MANUAL_Q::front() { + return q[head]; +} + +Operation_Logger_Type MANUAL_Q::back() { + return q[tail]; +} + +void MANUAL_Q::push(Operation_Logger_Type op) { + q[tail] = op; + counter++; + if (is_empty) + is_empty = false; + tail++; + tail %= Q_LEN; +} + +bool MANUAL_Q::empty() { + return is_empty; +} + +int MANUAL_Q::size() { + return counter; +} diff --git a/src/localization_module_lio_locus/src/point_cloud_odometry/CMakeLists.txt b/src/localization_module_lio_locus/src/point_cloud_odometry/CMakeLists.txt new file mode 100755 index 0000000..21d9fd9 --- /dev/null +++ b/src/localization_module_lio_locus/src/point_cloud_odometry/CMakeLists.txt @@ -0,0 +1,26 @@ + +add_library(point_cloud_odometry SHARED PointCloudOdometry.cc) + +#target_link_directories(point_cloud_odometry +# /home/demo/deps_install/lib +# ) + +target_link_libraries(point_cloud_odometry + glog + # ${PCL_LIBRARIES} + pcl_octree + pcl_filters + pcl_search + pcl_common + pcl_sample_consensus + ${YAML_CPP_LIBRARIES} +) + + +install(TARGETS point_cloud_odometry + DESTINATION lib +) + + + + diff --git a/src/localization_module_lio_locus/src/point_cloud_odometry/PointCloudOdometry.cc b/src/localization_module_lio_locus/src/point_cloud_odometry/PointCloudOdometry.cc new file mode 100755 index 0000000..cc1df5f --- /dev/null +++ b/src/localization_module_lio_locus/src/point_cloud_odometry/PointCloudOdometry.cc @@ -0,0 +1,307 @@ +/* + Authors: + - Matteo Palieri (matteo.palieri@jpl.nasa.gov) + - Benjamin Morrell (benjamin.morrell@jpl.nasa.gov) + - Andrzej Reinke (andrzej.m.reinke@jpl.nasa.gov) + */ + +#include +#include + +namespace gu = geometry_utils; +using pcl::copyPointCloud; +using namespace point_cloud_odometry; + +PointCloudOdometry::PointCloudOdometry() : + initialized_(false), b_use_imu_integration_(false) { + + query_.reset(new PointCloudF); + reference_.reset(new PointCloudF); + query_trans_.reset(new PointCloudF); + query_trans_->reserve(50000); + query_trans_->clear(); + + google::SetStderrLogging(google::GLOG_INFO); + FLAGS_colorlogtostderr = true; + FLAGS_alsologtostderr = true; +} + +PointCloudOdometry::~PointCloudOdometry() { +} + +bool PointCloudOdometry::Initialize(std::string path_to_file) { + + if (!loadParametersFromFile(path_to_file)) + return false; + + if (!SetupICP()) { + LOG(WARNING) << "Failed to SetupICP"; + } + + return true; +} + +void PointCloudOdometry::applyParameters() { + + double init_x = 0.0, init_y = 0.0, init_z = 0.0; + double init_qx = 0.0, init_qy = 0.0, init_qz = 0.0, init_qw = 1.0; + bool b_have_fiducial = true; + + double init_roll = 0.0, init_pitch = 0.0, init_yaw = 0.0; + gu::Quat q(gu::Quat(init_qw, init_qx, init_qy, init_qz)); + gu::Rot3 R; + R = gu::QuatToR(q); + init_roll = R.Roll(); + init_pitch = R.Pitch(); + init_yaw = R.Yaw(); + + integrated_estimate_.translation = gu::Vec3(init_x, init_y, init_z); + integrated_estimate_.rotation = gu::Rot3(init_roll, init_pitch, init_yaw); + + if (b_is_flat_ground_assumption_) { + integrated_estimate_.rotation = gu::Rot3(0, 0, + integrated_estimate_.rotation.Yaw()); + } + + if (!b_have_fiducial) { + LOG(WARNING) << "Can't find fiducials, using origin"; + + } else { + + + } + +} + +bool PointCloudOdometry::loadParametersFromFile(std::string path_to_file) { + + // if (!boost::filesystem::exists(path_to_file)) { + // ROS_DEBUG_STREAM(path_to_file); + // ROS_DEBUG_STREAM("file NOT exists for parameter loading!\n"); + // return false; + // } else { + // ROS_INFO_STREAM( + // "... reading parameter for lidar odometry from [" << path_to_file << "]!"); + + // } + + YAML::Node yaml_node = YAML::LoadFile(path_to_file); + b_is_flat_ground_assumption_ = yaml_node["b_is_flat_ground_assumption"].as< + bool>(); + + auto node_icp = yaml_node["icp"]; + + params_.registration_method = + node_icp["registration_method"].as(); + params_.num_threads = node_icp["num_threads"].as(); + + params_.icp_corr_dist = node_icp["corr_dist"].as(); + params_.icp_iterations = node_icp["iterations"].as(); + params_.icp_tf_epsilon = node_icp["tf_epsilon"].as(); + + params_.enable_timing_output = node_icp["enable_timing_output"].as(); + recompute_covariances_ = node_icp["recompute_covariances"].as(); + + transform_thresholding_ = node_icp["transform_thresholding"].as(); + max_translation_ = node_icp["max_translation"].as(); + max_rotation_ = node_icp["max_rotation"].as(); + + + return true; +} + +//------------------------------------------------------------------ + +bool PointCloudOdometry::SetupICP() { + + LOG(INFO) << "####################################################"; + LOG(INFO) << " PointCloudOdometry - SetupICP "; + LOG(INFO) << "####################################################"; + + RegistrationMethod method; + + if(params_.registration_method == "gicp") + method = RegistrationMethod::GICP; + else if (params_.registration_method == "ndt") + method = RegistrationMethod::NDT; + + switch (method) { + case RegistrationMethod::GICP: { + LOG(INFO) << "RegistrationMethod::GICP activated."; + pcl::MultithreadedGeneralizedIterativeClosestPoint::Ptr gicp = + boost::make_shared< + pcl::MultithreadedGeneralizedIterativeClosestPoint< + PointF, PointF> >(); + + gicp->setMaxCorrespondenceDistance(params_.icp_corr_dist); // for data association; + + gicp->setTransformationEpsilon(params_.icp_tf_epsilon); // for termination criteria in term of transformation deviation; + gicp->setEuclideanFitnessEpsilon(0.005); // for termination criteria in term of euclidean distance; + gicp->setMaximumIterations(params_.icp_iterations); // for termination criteria in term of iterations number; + + gicp->setRANSACIterations(0); + gicp->setNumThreads(params_.num_threads); + gicp->enableTimingOutput(params_.enable_timing_output); + gicp->RecomputeTargetCovariance(recompute_covariances_); + gicp->RecomputeSourceCovariance(recompute_covariances_); + + LOG(INFO) << "num_threads" << params_.num_threads; + LOG(INFO) << "getMaxCorrespondenceDistance: " << gicp->getMaxCorrespondenceDistance(); + LOG(INFO) << "getMaximumIterations: " << gicp->getMaximumIterations(); + LOG(INFO) << "getTransformationEpsilon: " << gicp->getTransformationEpsilon(); + + LOG(INFO) << "getEuclideanFitnessEpsilon: " << gicp->getEuclideanFitnessEpsilon(); + + LOG(INFO) << "Ransac: " << gicp->getRANSACIterations(); + + LOG(INFO) << "getRANSACIterations: " << gicp->getRANSACIterations(); + LOG(INFO) << " ROTATION EPSILION: " << gicp->getRotationEpsilon(); + LOG(INFO) << "getCorrespondenceRandomness:" << gicp->getCorrespondenceRandomness(); + LOG(INFO) << "getMaximumOptimizerIterations:" << gicp->getMaximumOptimizerIterations(); + LOG(INFO) << "getConvergeCriteria:" << gicp->getConvergeCriteria(); + LOG(INFO) << "RANSACOutlie: " << gicp->getRANSACOutlierRejectionThreshold(); + LOG(INFO) << "CLASS NAME: " << gicp->getClassName(); + + icp_ = gicp; + break; + } + case RegistrationMethod::NDT: { + LOG(INFO) << "RegistrationMethod::NDT activated."; + pclomp::NormalDistributionsTransform::Ptr ndt_omp = + boost::make_shared< + pclomp::NormalDistributionsTransform>(); + + ndt_omp->setTransformationEpsilon(params_.icp_tf_epsilon); + ndt_omp->setMaxCorrespondenceDistance(params_.icp_corr_dist); + ndt_omp->setMaximumIterations(params_.icp_iterations); + ndt_omp->setRANSACIterations(0); + ndt_omp->setNumThreads(params_.num_threads); + ndt_omp->enableTimingOutput(params_.enable_timing_output); + icp_ = ndt_omp; + break; + } + + default: + throw std::runtime_error( + "No such Registration mode or not implemented yet " + + params_.registration_method); + } + return true; +} + +void PointCloudOdometry::EnableImuIntegration() { + b_use_imu_integration_ = true; +} + +void PointCloudOdometry::DisableSensorIntegration() { + b_use_imu_integration_ = false; +} + +bool PointCloudOdometry::SetLidar(const PointCloudF &points) { + points_ = points; + return true; +} + +bool PointCloudOdometry::SetImuDelta(const Eigen::Matrix3d &imu_delta) { + imu_delta_ = imu_delta; + return true; +} + +bool PointCloudOdometry::UpdateEstimate() { + + if (!initialized_) { + copyPointCloud(points_, *query_); + initialized_ = true; + return false; + } else { + copyPointCloud(*query_, *reference_); + copyPointCloud(points_, *query_); + return UpdateICP(); + } +} + +// note:pior used here for matching come from prior transfered; +bool PointCloudOdometry::UpdateICP() { + query_trans_->clear(); + + // use IMU delta to update prior value; + if (b_use_imu_integration_) { + imu_prior_ << 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1; + imu_prior_.block(0, 0, 3, 3) = imu_delta_; + pcl::transformPointCloud(*query_, *query_trans_, imu_prior_); + } else { + *query_trans_ = *query_; + } + + icp_->setInputSource(query_trans_); + icp_->setInputTarget(reference_); + icp_->align(icpAlignedPointsOdometry_); + Eigen::Matrix4d T; + T = icp_->getFinalTransformation().cast(); + + if (b_use_imu_integration_) { + T = T * imu_prior_; + } + + geometry_utils::Rot3 rot_gu = gu::Rot3(T(0, 0), T(0, 1), T(0, 2), T(1, 0), + T(1, 1), T(1, 2), T(2, 0), T(2, 1), T(2, 2)); + + if (b_is_flat_ground_assumption_) { + double roll, pitch, yaw; + roll = rot_gu.Roll(); + pitch = rot_gu.Pitch(); + yaw = rot_gu.Yaw(); + + LOG(INFO) << "... using flat ground assumption in cloud odometry!"; + + incremental_estimate_.translation = gu::Vec3(T(0, 3), T(1, 3), 0); + incremental_estimate_.rotation = gu::Rot3(cos(yaw), -sin(yaw), 0, + sin(yaw), cos(yaw), 0, 0, 0, 1); + } else { + incremental_estimate_.translation = gu::Vec3(T(0, 3), T(1, 3), T(2, 3)); + incremental_estimate_.rotation = rot_gu; + } + + if (!transform_thresholding_ + || (incremental_estimate_.translation.Norm() <= max_translation_ + && incremental_estimate_.rotation.ToEulerZYX().Norm() + <= max_rotation_)) { + integrated_estimate_ = gu::PoseUpdate(integrated_estimate_, + incremental_estimate_); + } else { + LOG(WARNING) <<"%s: Discarding incremental transformation with norm (t: %lf, " + "r: %lf)", name_.c_str(), + incremental_estimate_.translation.Norm(), + incremental_estimate_.rotation.ToEulerZYX().Norm(); + } + + return true; +} + +void PointCloudOdometry::SetFlatGroundAssumptionValue(const bool &value) { + LOG(INFO) << + "PointCloudOdometry - SetFlatGroundAssumptionValue - Received: " << value; + b_is_flat_ground_assumption_ = value; + if (value) + integrated_estimate_.rotation = gu::Rot3(0, 0, + integrated_estimate_.rotation.Yaw()); +} + +const gu::Transform3& PointCloudOdometry::GetIncrementalEstimate() const { + return incremental_estimate_; +} + +const gu::Transform3& PointCloudOdometry::GetIntegratedEstimate() const { + return integrated_estimate_; +} + +bool PointCloudOdometry::GetLastPointCloud(PointCloudF::Ptr &out) const { + if (!initialized_ || query_ == NULL) { + + LOG(WARNING) <<"%s: Not initialized.", name_.c_str(); + return false; + } + out = query_; + return true; +} +